Skip to content
Snippets Groups Projects
Commit 6773a4ac authored by Max Maria Humbert's avatar Max Maria Humbert
Browse files

final changes notebooks

parent c43501e8
No related branches found
No related tags found
1 merge request!4dev-max into develop
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## MoveIt Basics
### Task 2
---
> In this task, you will learn ...
>
> - ... how to move the robot to a specific cartesian position.
> - ... how to determine the joint values that represent a Cartesian position (alternative).
---
%% Cell type:markdown id: tags:
As always, we need to start by implementing the required modules.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import sys
import rospy
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Next, we need to initialize ``roscpp``, set up a ``ROS node``, and implement a ``MoveGroupCommander`` instance.
ToDo:
- initialize ``roscpp`` with ``sys.argv`` as an argument
- initialize a ``ROS node``
- assign a ``MoveGroupCommander`` instace to ``group``
- assign a ``MoveGroupCommander`` instance to ``group``
%% Cell type:code id: tags:
```
group = None
##### YOUR CODE HERE #####
roscpp_initialize(sys.argv)
rospy.init_node('commander', anonymous=True)
group = MoveGroupCommander("panda_arm")
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
To speed up the movement with the ``MoveIt Commander``, you can adjust the ``set_max_velocity_scaling_factor()`` and ``set_max_acceleration_scaling_factor()`` of the ``MoveGroupCommander`` object. Set both to ``1``.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
group.set_max_velocity_scaling_factor(1.0)
group.set_max_acceleration_scaling_factor(1.0)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Next, we retrieve the robot's current Cartesian pose and modify it as needed. The Cartesian coordinates ``position.x``, ``position.y``, and ``position.z`` represent the position of the ``gripper`` in 3D space, where (0, 0, 0) corresponds to the robot's base. The orientation is described by ``orientation.x``, ``orientation.y``, ``orientation.z`` and ``orientation.w``, which define the angular position of the gripper.
- ``orientation.x``, ``orientation.y``, ``orientation.z`` represent the axis of rotation of the gripper.
- ``orientation.w`` represents the magnitude of the rotation about this axis.
Since the orientation values use a ``quaternion`` representation, they must satisfy the normalization condition:
$$x^2 + y^2 + z^2 + w^2 = 1$$
<img src="https://leimao.github.io/images/blog/2022-04-20-3D-Rotation-Unit-Quaternion/quaternion.png"
alt="joints of the panda robot" width="200">
ToDo:
- set the ``position.y`` to 0.0 and ``position.z`` to 0.2
- set the ``orientation -y, -z, -w`` to 0.5
%% Cell type:code id: tags:
```
target_pose = group.get_current_pose().pose
target_pose.position.x = 0.5
target_pose.orientation.x = 0.5
##### YOUR CODE HERE #####
target_pose.position.y = 0.0
target_pose.position.z = 0.2
target_pose.orientation.y = 0.5
target_pose.orientation.z = 0.5
target_pose.orientation.w = 0.5
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Next, we aim to retrieve the joint values required to move the ``gripper`` to specific Cartesian positions. To achieve this, we use the ``plan()`` method of the ``MoveGroupCommander``. This method generates a motion plan to the defined goal state, essentially providing a sequence of joint values the robot must follow to reach the target joint state. Our focus is on extracting the last joint values in the sequence, representing the final goal corresponding to the target Cartesian position. Check the terminal to verify if the final goal joint values remain consistent for the same Cartesian position (look for the 'Output of Robot Script:' lines).
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
for i in range(5):
plan = group.plan(target_pose)
point_list = plan[1].joint_trajectory.points
last_point = point_list[-1].positions
rospy.loginfo(last_point)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
If done correctly, you might notice that the joint values are sometimes slightly different, and sometimes the +/ - signs are inverted. This happens because there isn’t just one correct solution. Different joint configurations can result in the same Cartesian position.
Finally, we set the target Cartesian pose using the ``set_pose_target()`` method of the ``MoveGroupCommander`` and execute the motion with the ``go()`` method.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
group.set_pose_target(target_pose)
group.go(wait=True)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
At the end, we need to shut everything down.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## ROS Basics
### Task 1
---
> In this task, you will learn ...
>
> - ... what ROS is.
> - ... the essential functions and classes provided by ROS.
> - ... how to create a simple Publisher using the ``rospy`` python API.
---
%% Cell type:markdown id: tags:
The ``Robot Operating System (ROS)`` is an open-source framework that simplifies the development of robot software. At its core, ``ROS`` uses:
- ``Topics``, which are named communication channels used to exchange messages. ``Nodes`` can publish data to a ``topic`` to send data or subscribe to a ``topic`` to receive the data being published on this ``topic``.
- ``Nodes``, which is basically a process that performs computation, similar to an executable program running inside your application. Communicates with other ``ROS nodes`` using ``topics``.
- ``Messages``, which describe the data values that ``ROS nodes`` publish.
- ``Services``, which provides a request/ reply model. A client calls a ``service`` by sending the request message and awaiting the reply. Unlike the many-to-many communication of the publish/ subscribe model.
%% Cell type:markdown id: tags:
To use the ``ROS`` Python API, the ``rospy`` library must first be imported. Since we want to exchange regular strings later, we need to import the String message type. Additionally, the standard Python module ``time`` is used for handling time calculations.
To use the ``ROS`` Python API, the ``rospy`` library must first be imported. Since we want to exchange regular strings later, we need to import the String message type ``std_msgs.msg``. Additionally, the standard Python module ``time`` is used for handling time calculations.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import time
from std_msgs.msg import String
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Next, we want to create our first ``ROS node``, which will later ``publish`` string messages to a specific ``topic`` of our choice. For this we set the name of our node to ``'publisher_node'``. The ``anonymous=True`` argument ensures that the node name is unique by appending a random number to it.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.init_node('publisher_node', anonymous=True)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now we want to create a ``Publisher`` that sends Strings messages to the ``'chatter'`` topic.
Now we want to create a ``Publisher`` that sends ``Strings`` messages to the ``'chatter'`` topic. The ``queue_size`` argument specifies the number of messages that can be held in a buffer when ``subscribers`` to the ``topic`` are not immediately ready to process them.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
pub = rospy.Publisher('/chatter', String, queue_size=10)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Next, we will ``publish`` the String message in a loop at a rate of 10Hz, using the ``rospy.Rate()`` method in combination with a while loop. To maintain the 10Hz loop rate, ``ROS`` provides the ``rate.sleep()`` method. For better practice, we will allow the publisher to publish messages continuously for 15 seconds.
ToDo:
- Set the loop rate to 10Hz by modify the ``rate`` variable and
- call the ``publish()`` method of the Publisher to send the message.
%% Cell type:code id: tags:
```
t = time.time()
rate = None
##### YOUR CODE HERE #####
rate = rospy.Rate(10)
##### YOUR CODE HERE #####
while not rospy.is_shutdown():
msg = 'Hello, ROS!'
##### YOUR CODE HERE #####
pub.publish(msg)
##### YOUR CODE HERE #####
rate.sleep()
if time.time() - t > 15:
break
```
%% Cell type:markdown id: tags:
While ``ROS`` is running, we aim to keep the ``ROS nodes`` as clean as possible, so we will delete any ``ROS node`` that is no longer needed afterwards.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed.")
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## ROS Basics
### Task 2
---
> In this task, you will learn ...
>
> - ... how to create a simple ``ROS`` topic subscriber.
---
%% Cell type:markdown id: tags:
First we need to import the Modules.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import time
import sys
from std_msgs.msg import String
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
In the background, we will have a ``ROS node`` that ``publishes`` String messages on the ``/notification`` ``topic``. First, we need to initialize the ``callback()`` method of the ``Subscriber``. If the ``Subscriber`` receives any messages on the subscribed ``topic``, it will call a method that we specify, passing the received message as an argument to this method. We want our callback method to just log the incoming data with the ``rospy.loginfo()`` method.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
def callback(msg):
rospy.loginfo("data: " + msg.data)
sys.stdout.flush()
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now, we will specify the ``Subscriber``. First, we initialize a ``ROS node``. Then, we set the ``topic`` that the subscriber should listen to to ``/notification``. We also define the data type of the received messages as ``String`` and specify the method that the subscriber should call if data is published on this ``topic``, passing the received data as an argument.
ToDo:
- initialize the ``ROS node`` with the name ``'subscriber_node'``
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
rospy.init_node("subscriber_node", anonymous=True)
##### YOUR CODE HERE #####
rospy.Subscriber("/notification", String, callback)
```
%% Cell type:markdown id: tags:
For better practice, we will allow the ``Subscriber`` to listen continuously for 15 seconds.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
t = time.time()
while not rospy.is_shutdown():
if time.time() - t > 15:
break
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
After that we delete the ``ROS node``. Now, when you execute the script, you'll observe that the ``subscriber`` collects incoming data — in this case, random integers between 1 and 100 — and prints them out.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed.")
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## ROS Basics
### Task 3
---
> In this task, you will learn ...
>
> - ... useful ``ROS`` command-line tools.
> - ... useful ``ROS topics`` for working with the Panda Robot.
---
%% Cell type:markdown id: tags:
### Useful ROS tools
%% Cell type:markdown id: tags:
ROS offers users very useful command-line tools that assist in working with and debugging ROS-based systems. In this section of the exercise, we will introduce our top three command-line tools. Let’s begin with the ``rostopic`` tool, which provides several handy commands:
- ``rostopic list``: Displays all active topics.
- ``rostopic echo /topic_name``: Shows messages being published to the topic.
- ``rostopic info /topic_name``: Prints detailed information about the topic.
Try it yourself: list all active ``topics``, pick one, display its detailed information using ``rostopic info /topic_name``, and review the messages published to it. If you’re unsure which topic to select, try ``/franka_state_controller/franka_states``.
%% Cell type:markdown id: tags:
The next essential command-line tool is ``rosnode``, which provides several helpful commands:
- ``rosnode list``: Displays all active nodes.
- ``rosnode ping /node_name``: Tests connectivity to the node.
- ``rosnode info /node_name``: Prints detailed information about the node.
Try it out yourself: list all active ``nodes``, select a ``node``, test its connectivity using ``rosnode ping /node_name``, and retrieve detailed information. A good choice might be the ``/joint_state_publisher`` node.
%% Cell type:markdown id: tags:
Last but not least, the ``rqt_graph`` is an useful tool. It visualizes a graph of nodes and topics, making it much easier to understand the system architecture. Simply run ``rqt_graph``, and it will display the ``nodes`` along with their ``publishers`` and ``subscribers``.
Try it out yourself.
%% Cell type:markdown id: tags:
### Useful ROS topics for the panda robot
%% Cell type:markdown id: tags:
The Panda Robot is a 7-axis robotic arm with a gripper/ finger.
- ``/joint_states``: on this topic the current joints position, velocity and effort are published and the message type is JointState
- ``/joint_states``: on this topic the current joint positions, velocity and effort are published and the message type is JointState
- ``/franka_state_controller/franka_states ``: on this topic the pose of the end-effector (gripper) relative to the robot's base frame, robot_mode, control_mode and many more are published. It uses the message type FrankaState.
- ``/tf``: contains metadata that describes the translation and rotation (quaternion) between two frames
- etc.
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## ROS Intermediate
### Task 1
---
> In this task, you will learn ...
>
> - ... how to rotate the joints of the robot using rostopics.
---
%% Cell type:markdown id: tags:
Now that we understand how ``ROS`` works, let's use this knowledge to control the joints of the Panda robot. To do this, we first need to import ``rospy``, the Python API for ``ROS``, along with some essential libraries such as ``math``. Additionally, we will need specific message types that the robot can interpret and execute to perform the desired movements.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import math
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from sensor_msgs.msg import JointState
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now, let's start with initializing a ``ROS node`` and creating a ``Publisher``. The ``Publisher`` will later publish our target joint values to the correct topic.
ToDo:
- create a ``ROS node`` with the name ``joint_manipulator``
- implement the `Publisher` that publishes data to the ``/effort_joint_trajectory_controller`` topic using the JointTrajectory message type
%% Cell type:code id: tags:
```
pub = None
##### YOUR CODE HERE #####
rospy.init_node("joint_manipulator")
pub = rospy.Publisher('/effort_joint_trajectory_controller/command', JointTrajectory, queue_size=10)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Next, we need to initialize the message that will hold the target values, which will later be published to control the robot's movements. To do this, we create an object of the ``JointTrajectory`` class, set the header, and then add the joint_names that we want to modify. The ``JointTrajectory`` is a message type used to define the movement of the robot's joints over time.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
joint_trajectory = JointTrajectory()
joint_trajectory.header.stamp = rospy.Time.now()
joint_trajectory.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
To the ``JointTrajectory``, we can add ``JointTrajectoryPoints``, which the robot will then execute sequentially. To do this, we need to create a ``JointTrajectoryPoint`` and add the desired values for the movement. We initial set the values of our target point to the current joint values of the robot.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
point = JointTrajectoryPoint()
current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position
point.positions = list(current_joint_values)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
<img src="https://www.researchgate.net/publication/378309540/figure/fig2/AS:11431281224653965@1708362343804/The-7DoF-Franka-Emika-Panda-robot-arm.jpg"
alt="joints of the panda robot" width="350">
Each axis of the robot can only rotate within a specific range, defined by a minimum and maximum radiant value.
> - joint0: [-2.8973, 2.8973]
> - joint1: [-1.7628, 1.7628]
> - joint2: [-2.8973, 2.8973]
> - joint3: [-3.0718, -0.0698]
> - joint4: [-2.8973, 2.8073]
> - joint5: [-0.0175, 3.7525]
> - joint6: [-2.8973, 2.8973]
ToDo:
- rotate the joint1 to 90 degrees,
- rotate the joint4 to 155 degrees.
Tip:
- use ``math.pi``
- $$degrees = 180 * randiant / pi$$
%% Cell type:code id: tags:
```
point.positions[0] = 0.0
##### YOUR CODE HERE #####
point.positions[2] = 0.5 * math.pi
point.positions[4] = 0.75 * math.pi
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
To complete the script, we can set the duration of the movement, append the point to the ``JointTrajectory``, and then, after a short pause, publish our message.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
point.time_from_start = rospy.Duration(2)
joint_trajectory.points.append(point)
rospy.sleep(1.0)
pub.publish(joint_trajectory)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
At the end, sleep for the same duration as the movement to ensure nothing interrupts it. Finally, don’t forget to shut down the node when the process is complete.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.sleep(2)
rospy.signal_shutdown("Task completed")
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## ROS Intermediate
### Task 2
---
> In this task, you will ...
>
> - ... execute multiple movements of the robot on your own.
---
%% Cell type:markdown id: tags:
First import ``rospy``, ``math``, ``JointTrajectory`` and ``JointTrajectoryPoint``.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import math
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from sensor_msgs.msg import JointState
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Initialize a subscriber node by first creating the ``ROS node``. Then, define a ``subscriber`` within this node, selecting the appropriate ``topic`` and ensuring that the correct message type is specified.
Initialize a publisher node by first creating the ``ROS node``. Then, define a ``publisher`` within this node, selecting the appropriate ``topic`` and ensuring that the correct message type is specified.
ToDo:
- create ``ROS node``
- implement a ``publisher`` to the ``pub`` variable
%% Cell type:code id: tags:
```
pub = None
##### YOUR CODE HERE #####
rospy.init_node("joint_manipulator")
pub = rospy.Publisher('/effort_joint_trajectory_controller/command', JointTrajectory, queue_size=10)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
As in Task 1, we then proceed to create a ``JointTrajectory`` object.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
joint_trajectory = JointTrajectory()
joint_trajectory.header.stamp = rospy.Time.now()
joint_trajectory.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Next, add three points to the ``JointTrajectory`` object. In the first point, set ``joint6`` to ``155`` degrees. For the second point, set the joint positions to ``[-1.5, -0.5, 0, -1.5, 0, 1.5, 0]``. In the final point, reset the robot to its default position. That would be ``[0, -45, 0, -135, 0, 90, 45]`` degrees. Set the time_from_start variable correctly to 2, 4 and 6 seconds.
Next, add three points to the ``JointTrajectory`` object. For the first point, change a single joint. For the second point, set the joint positions to a completly new position. In the final point, reset the robot to its default position. That would be ``[0, -45, 0, -135, 0, 90, 45]`` degrees. Set the ``time_from_start`` variable correctly to 2, 4 and 6 seconds.
ToDo:
- point1: set ``joint6`` to ``155`` degrees
- point2: set to ``[-1.5, -0.5, 0, -1.5, 0, 1.5, 0]``
- point3: set to default position
- set the ``time_from_start``
- append the points to the ``joint_trajectory``
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
point1 = JointTrajectoryPoint()
point2 = JointTrajectoryPoint()
point3 = JointTrajectoryPoint()
##### YOUR CODE HERE #####
current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position
point1.positions = list(current_joint_values)
point2.positions = list(current_joint_values)
point3.positions = list(current_joint_values)
point1.positions[6] = math.pi * 3/4
point2.positions[0] = -1.5
point2.positions[1] = -0.5
point2.positions[2] = 0.0
point2.positions[3] = -1.5
point2.positions[4] = 0.0
point2.positions[5] = 1.5
point2.positions[6] = 0.0
point1.time_from_start = rospy.Duration(2)
point2.time_from_start = rospy.Duration(4)
point3.time_from_start = rospy.Duration(6)
joint_trajectory.points.append(point1)
joint_trajectory.points.append(point2)
joint_trajectory.points.append(point3)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
We now publish the ``JointTrajectory`` message, allow the robot 6 seconds to execute the movement, and then delete the ``node``.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.sleep(2)
pub.publish(joint_trajectory)
rospy.sleep(6)
rospy.signal_shutdown("Task completed.")
##### DO NOT CHANGE #####
```
......
%% Cell type:markdown id: tags:
# Learn Environment Panda Robot
Author: NAME
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## Task_Name
### Subtask_Name
### Task X
---
> In this task, you will learn ...
>
> - ...
> - ...
---
%% Cell type:markdown id: tags:
Code cell that students should not modify. It is a good practice (but not mandatory) to use the `#### DO NOT CHANGE ####` tag to indicate this.
It's a good practice to tell the user, what the code in the cell does.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
print("Code that should not be changed by the user.")
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
This markdown cell outlines the tasks to be implemented in the subsequent code cell.
**Do this:**
- Implement this
- Implement that
---
All user-implemented code must be placed between two `##### YOUR CODE HERE #####` tags. Ensure you match this syntax exactly.
The placeholder code between the tags will be:
```
##### YOUR CODE HERE #####
raise NotImplementedError()
```
%% Cell type:code id: tags:
```
print ("This is given code that won't be replaced")
##### YOUR CODE HERE #####
print ("This is the solution code that will be replaced")
##### YOUR CODE HERE #####
print ("This is given code that won't be replaced")
if (True):
##### YOUR CODE HERE #####
print ("You can also use indentation but also need to indent the 'YOUR CODE HERE' line accordingly")
# comments will also be replaced
print ("This is the solution code that will be replaced")
##### YOUR CODE HERE #####
print ("This is given code that won't be replaced")
```
%% Cell type:markdown id: tags:
Feel free to add more cells as needed. Ensure that your code is executable and follows the provided guidelines.
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment