Stretch ROS driver offers a [`FollowJointTrajectory`](http://docs.ros.org/en/api/control_msgs/html/action/FollowJointTrajectory.html) action service for its arm. Within this tutorial we will have a simple FollowJointTrajectory commands sent to a Stretch robot to execute.
Stretch ROS driver offers a [`FollowJointTrajectory`](http://docs.ros.org/en/api/control_msgs/html/action/FollowJointTrajectory.html) action service for its arm. Within this tutorial we will have a simple FollowJointTrajectory command sent to a Stretch robot to execute.
## Stow Command Example
<palign="center">
@ -21,7 +21,7 @@ cd catkin_ws/src/stretch_ros_turotials/src/
python3 stow_command.py
```
This will sent FollowJointTrajectory commands to stow Stretch's arm.
This will send a FollowJointTrajectory command to stow Stretch's arm.
### The Code
```python
@ -138,3 +138,121 @@ if __name__ == '__main__':
```
Initialize the `StowCommand()` class and set it to *node* and run the `main()` function.
## Multipoint Command Example
<palign="center">
<imgsrc="images/multipoint.gif"/>
</p>
Begin by running `roscore` in a terminal. Then set the ros parameter to *position* mode by running the following commands in a new terminal.
```bash
rosparam set /stretch_driver/mode "position"
roslaunch stretch_core stretch_driver.launch
```
In a new terminal type the following commands.
```bash
cd catkin_ws/src/stretch_ros_turotials/src/
python3 multipoint_command.py
```
This will send a list of JointTrajectoryPoint's to move Stretch's arm.
### The Code
```python
#!/usr/bin/env python3
import rospy
import time
from control_msgs.msg import FollowJointTrajectoryGoal
from trajectory_msgs.msg import JointTrajectoryPoint
rospy.loginfo('interrupt received, so shutting down')
```
### The Code Explained.
Seeing that there are similarities between the multipoint and stow command nodes, we will only breakdown the different components of the multipoint_command node.
```python
point0 = JointTrajectoryPoint()
point0.positions = [0.2, 0.0, 3.4]
```
Sett *point0* as a `JointTrajectoryPoint`and provide desired positions (in meters). These are the positions of the lift, wrist extension, and yaw of the wrist, respectively.
```python
point0.velocities = [0.2, 0.2, 2.5]
```
Provide desired velocity of the lift (m/s), wrist extension (m/s), and wrist yaw (rad/s) for *point0*.
```python
point0.accelerations = [1.0, 1.0, 3.5]
```
Provide desired velocity of the lift (m/s^2), wrist extension (m/s^2), and wrist yaw (rad/s^2).
**IMPORTANT NOTE**: The lift and wrist extension can only go up to 0.2 m/s. If you do not provide any velocities or accelerations for the lift or wrist extension, then they go to their default values. However, the Velocity and Acceleration of the wrist yaw will stay the same from the previous value unless updated.
Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` is defined by a list of the 6 points. Specify the coordinate frame that we want (base_link) and set the time to be now.