@ -130,5 +130,3 @@ When coming up with this guide, we expected the following:
* Body-mounted accessories with the same ID numbers mounted to different robots could be disambiguated using the expected range of 3D locations of the ArUco markers on the calibrated body.
* Accessories in the environment with the same ID numbers could be disambiguated using a map or nearby observable features of the environment.
@ -12,13 +12,13 @@ Begin by running the following command in a new terminal.
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *navigation* mode using a rosservice call. Then drive the robot forward with the move node.
Switch the mode to *navigation* mode using a rosservice call. Then drive the robot forward with the [move.py](https://github.com/hello-robot/stretch_tutorials/tree/noetic/src) node.
```bash
# Terminal 2
rosservice call /switch_to_navigation_mode
cd catkin_ws/src/stretch_tutorials/src/
python move.py
python3 move.py
```
To stop the node from sending twist messages, type **Ctrl** + **c**.
@ -26,14 +26,14 @@ To stop the node from sending twist messages, type **Ctrl** + **c**.
Below is the code which will send *Twist* messages to drive the robot forward.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import Twist
class Move:
"""
A class that sends Twist messages to move the Stretch robot foward.
A class that sends Twist messages to move the Stretch robot forward.
"""
def __init__(self):
"""
@ -72,16 +72,16 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
from geometry_msgs.msg import Twist
```
You need to import rospy if you are writing a ROS Node. The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
```python
@ -89,21 +89,20 @@ class Move:
def __init__(self):
self.pub = rospy.Publisher('/stretch/cmd_vel', Twist, queue_size=1)#/stretch_diff_drive_controller/cmd_vel for gazebo
```
This section of code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1)` declares that your node is publishing to the /stretch/cmd_vel topic using the message type Twist. The queue_size argument limits the amount of queued messages if any subscriber is not receiving them fast enough.
This section of code defines the talker's interface to the rest of ROS. `pub = rospy.Publisher("/stretch/cmd_vel", Twist, queue_size=1)` declares that your node is publishing to the */stretch/cmd_vel* topic using the message type `Twist`. The `queue_size` argument limits the amount of queued messages if any subscriber is not receiving them fast enough.
```Python
command = Twist()
```
Make a Twist message. We're going to set all of the elements, since we
can't depend on them defaulting to safe values.
Make a `Twist` message. We're going to set all of the elements, since we can't depend on them defaulting to safe values.
```python
command.linear.x = 0.1
command.linear.y = 0.0
command.linear.z = 0.0
```
A Twist has three linear velocities (in meters per second), along each of the axes. For Stretch, it will only pay attention to the x velocity, since it can't directly move in the y direction or the z direction.
A `Twist` data structure has three linear velocities (in meters per second), along each of the axes. For Stretch, it will only pay attention to the x velocity, since it can't directly move in the y direction or the z direction.
```python
@ -111,30 +110,29 @@ command.angular.x = 0.0
command.angular.y = 0.0
command.angular.z = 0.0
```
A *Twist* also has three rotational velocities (in radians per second).
The Stretch will only respond to rotations around the z (vertical) axis.
A `Twist` message also has three rotational velocities (in radians per second). The Stretch will only respond to rotations around the z (vertical) axis.
```python
self.pub.publish(command)
```
Publish the Twist commands in the previously defined topic name */stretch/cmd_vel*.
Publish the `Twist` commands in the previously defined topic name */stretch/cmd_vel*.
```Python
rospy.init_node('move')
base_motion = Move()
rate = rospy.Rate(10)
```
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
The `rospy.Rate()` function creates a Rate object rate. With the help of its method `sleep()`, it offers a convenient way for looping at the desired rate. With its argument of 10, we should expect to go through the loop 10 times per second (as long as our processing time does not exceed 1/10th of a second!)
The `rospy.Rate()` function creates a Rate object. With the help of its method `sleep()`, it offers a convenient way for looping at the desired rate. With its argument of 10, we should expect to go through the loop 10 times per second (as long as our processing time does not exceed 1/10th of a second!)
```python
while not rospy.is_shutdown():
base_motion.move_forward()
rate.sleep()
```
This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check is_shutdown() to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop.
This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check `is_shutdown()` to check if your program should exit (e.g. if there is a **Ctrl-C** or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop.
## Move Stretch in Simulation
@ -142,7 +140,7 @@ This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown(
<imgsrc="images/move.gif"/>
</p>
Using your preferred text editor, modify the topic name of the published *Twist* messages. Please review the edit in the **move.py** script below.
Using your preferred text editor, modify the topic name of the published `Twist` messages. Please review the edit in the **move.py** script below.
Then run the tf2 broadcaster node to visualize three static frames.
Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_broadcaster.py) node to visualize three static frames.
```bash
# Terminal 3
cd catkin_ws/src/stretch_tutorials/src/
python tf2_broadcaster.py
python3 tf2_broadcaster.py
```
The gif below visualizes what happens when running the previous node.
@ -32,15 +31,14 @@ The gif below visualizes what happens when running the previous node.
<imgsrc="images/tf2_broadcaster.gif"/>
</p>
**OPTIONAL**: If you would like to see how the static frames update while the robot is in motion, run the stow command node and observe the tf frames in RViz.
**OPTIONAL**: If you would like to see how the static frames update while the robot is in motion, run the [stow_command_node.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/stow_command.py) and observe the tf frames in RViz.
```bash
# Terminal 4
cd catkin_ws/src/stretch_tutorials/src/
python stow_command.py
python3 stow_command.py
```
<palign="center">
<imgsrc="images/tf2_broadcaster_with_stow.gif"/>
</p>
@ -49,7 +47,7 @@ python stow_command.py
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import tf.transformations
@ -124,9 +122,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
@ -134,8 +132,7 @@ import tf.transformations
from geometry_msgs.msg import TransformStamped
from tf2_ros import StaticTransformBroadcaster
```
You need to import rospy if you are writing a ROS Node. Import `tf.transformations` to get quaternion values from Euler angles. Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.StaticTransformBroadcaster` to help make the task of publishing transforms easier.
You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import `tf.transformations` to get quaternion values from Euler angles. Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.StaticTransformBroadcaster` to help make the task of publishing transforms easier.
```python
def __init__(self):
@ -146,7 +143,6 @@ def __init__(self):
"""
self.br = StaticTransformBroadcaster()
```
Here we create a `TransformStamped` object which will be the message we will send over once populated.
We need to give the transform being published a timestamp, we'll just stamp it with the current time, `rospy.Time.now()`. Then, we need to set the name of the parent frame of the link we're creating, in this case *link_mast*. Finally, we need to set the name of the child frame of the link we're creating. In this instance, the child frame is *fk_link_mast*.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate the class with `FixedFrameBroadcaster()`
Instantiate the `FixedFrameBroadcaster()` class.
```python
rospy.spin()
@ -198,7 +193,6 @@ messages come in. If we don't put this line in, then the node will not work,
and ROS will not process any messages.
## tf2 Static Listener
In the previous section of the tutorial, we created a tf2 broadcaster to publish three static transform frames. In this section we will create a tf2 listener that will find the transform between *fk_link_lift* and *link_grasp_center*.
@ -208,23 +202,20 @@ Begin by starting up the stretch driver launch file.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Then run the tf2 broadcaster node to create the three static frames.
Then run the [tf2_broadcaster.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_broadcaster.py) node to create the three static frames.
```bash
# Terminal 2
cd catkin_ws/src/stretch_tutorials/src/
python tf2_broadcaster.py
python3 tf2_broadcaster.py
```
Finally, run the tf2 listener node to print the transform between two links.
Finally, run the [tf2_listener.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/tf2_listener.py) node to print the transform between two links.
```bash
# Terminal 3
cd catkin_ws/src/stretch_tutorials/src/
python tf2_listener.py
python3 tf2_listener.py
```
Within the terminal the transform will be printed every 1 second. Below is an example of what will be printed in the terminal. There is also an image for reference of the two frames.
```bash
@ -248,7 +239,7 @@ rotation:
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import TransformStamped
@ -261,7 +252,7 @@ class FrameListener():
"""
def __init__(self):
"""
A function that initializes the variables and looks up a tranformation
A function that initializes the variables and looks up a transformation
between a target and source frame.
:param self: The self reference.
"""
@ -296,9 +287,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
@ -306,7 +297,7 @@ from geometry_msgs.msg import TransformStamped
import tf2_ros
```
You need to import rospy if you are writing a ROS Node. Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.TransformListener` to help make the task of receiving transforms easier.
You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `TransformStamped` from the `geometry_msgs.msg` package because we will be publishing static frames and it requires this message type. The `tf2_ros` package provides an implementation of a `tf2_ros.TransformListener` to help make the task of receiving transforms easier.
```python
tf_buffer = tf2_ros.Buffer()
@ -324,7 +315,6 @@ Store frame names in variables that will be used to compute transformations.
rospy.sleep(1.0)
rate = rospy.Rate(1)
```
The first line gives the listener some time to accumulate transforms. The second line is the rate the node is going to publish information (1 Hz).
rospy.logwarn(' Could not transform %s from %s ', to_frame_rel, from_frame_rel)
```
Try to look up the transform we want. Use a try-except block, since it may fail on any single call, due to internal timing issues in the transform publishers. Look up transform between *from_frame_rel* and *to_frame_rel* frames with the `lookup_transform()` function.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate the class with `FrameListener()`
Instantiate the `FrameListener()` class.
```python
rospy.spin()
```
Give control to ROS. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
**Previous Example** [Voice Teleoperation of Base](example_9.md)
@ -8,30 +8,25 @@ Begin by starting up the stretch driver launch file.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
To activate the RealSense camera and publish topics to be visualized, run the following launch file in a new terminal.
To activate the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/) and publish topics to be visualized, run the following launch file in a new terminal.
Then run the [pointCloud_transformer.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/pointcloud_transformer.py) node.
```bash
# Terminal 3
cd catkin_ws/src/stretch_tutorials/src/
python pointcloud_transformer.py
python3 pointcloud_transformer.py
```
Within this tutorial package, there is an RViz config file with the `PointCloud` in the Display tree. You can visualize this topic and the robot model by running the command below in a new terminal.
rospy.loginfo('Publishing transformed PointCloud. Use RViz to visualize')
def callback_pcl2(self,msg):
@ -98,7 +93,7 @@ class PointCloudTransformer:
:param self: The self reference.
:param msg: The PointCloud message.
:returns new_cloud: PointCloud message.
:returns new_cloud: The transformed PointCloud message.
"""
while not rospy.is_shutdown():
try:
@ -124,9 +119,9 @@ if __name__=="__main__":
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
@ -136,8 +131,7 @@ from sensor_msgs.msg import PointCloud2, PointCloud
from geometry_msgs.msg import Point32
from std_msgs.msg import Header
```
You need to import `rospy` if you are writing a ROS Node. Import `tf` to utilize the `transformPointCloud` function. Import various the message types from `sensor_msgs`.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import `tf` to utilize the `transformPointCloud` function. Import various the message types from `sensor_msgs`.
This section of code defines the talker's interface to the rest of ROS. `self.pointcloud_pub = rospy.Publisher("/camera_cloud", PointCloud, queue_size=1)` declares that your node is publishing to the */camera_cloud* topic using the message type `PointCloud`.
The first line of code initializes *self.pcl2_cloud* to store the `PointCloud2` message. The second line creates a `tf.TransformListener` object. Once the listener is created, it starts receiving tf transformations over the wire, and buffers them for up to 10 seconds.
```python
@ -172,20 +164,17 @@ The callback function that stores the the `PointCloud2` message.
temp_cloud = PointCloud()
temp_cloud.header = self.pcl2_cloud.header
```
Create a `PointCloud` for temporary use. Set the temporary PointCloud's header to the stored PointCloud2 header.
Create a `PointCloud` for temporary use. Set the temporary PointCloud's header to the stored `PointCloud2` header.
```python
for data in pc2.read_points(self.pcl2_cloud, skip_nans=True):
Try to look up and transform the `PointCloud` input. Use a try-except block, since it may fail on any single call, due to internal timing issues in the transform publishers. Transform the point cloud data from *camera_color_optical_frame* to *base_link* with the `transformPointCloud()` function.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Declare object, *PCT*, from the `PointCloudTransformer` class.
Declare a `PointCloudTransformer` object.
```python
rate = rospy.Rate(1)
rospy.sleep(1)
```
The first line gives the listener some time to accumulate transforms. The second line is the rate the node is going to publish information (1 Hz).
```python
# Run while loop until the node is shutdown
while not rospy.is_shutdown():
# Run the pcl_transformer method
PCT.pcl_transformer()
rate.sleep()
```
Run a while loop until the node is shutdown. Within the while loop run the `pcl_transformer()` method.
**Previous Example** [Tf2 Broadcaster and Listener](example_10.md)
**Next Example** [ArUco Tag Locator](example_12.md)
Run a while loop until the node is shutdown. Within the while loop run the `pcl_transformer()` method.
@ -194,7 +192,6 @@ class LocateArUcoTag(hm.HelloNode):
rospy.loginfo('Searching for docking ArUco tag.')
pose = self.find_tag("docking_station")
if __name__ == '__main__':
try:
node = LocateArUcoTag()
@ -208,9 +205,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
@ -226,7 +223,7 @@ from trajectory_msgs.msg import JointTrajectoryPoint
from geometry_msgs.msg import TransformStamped
```
You need to import rospy if you are writing a ROS Node. Import other python modules needed for this node. Import the FollowJointTrajectoryGoal from the [control_msgs.msg](http://wiki.ros.org/control_msgs) package to control the Stretch robot. Import JointTrajectoryPoint from the [trajectory_msgs](http://wiki.ros.org/trajectory_msgs) package to define robot trajectories. The [hello_helpers](https://github.com/hello-robot/stretch_ros/tree/master/hello_helpers) package consists of a module the provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance we are importing the hello_misc script.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import other python modules needed for this node. Import the `FollowJointTrajectoryGoal` from the [control_msgs.msg](http://wiki.ros.org/control_msgs) package to control the Stretch robot. Import `JointTrajectoryPoint` from the [trajectory_msgs](http://wiki.ros.org/trajectory_msgs) package to define robot trajectories. The [hello_helpers](https://github.com/hello-robot/stretch_ros/tree/master/hello_helpers) package consists of a module the provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance we are importing the `hello_misc` script.
```python
def __init__(self):
@ -241,7 +238,6 @@ def __init__(self):
self.joint_state = None
```
The `LocateArUcoTag` class inherits the `HelloNode` class from `hm` and is instantiated.
Set up a subscriber with `rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)`. We're going to subscribe to the topic "*stretch/joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function `joint_states_callback()` automatically.
Provide the minimum and maximum joint positions for the head pan. These values are needed for sweeping the head to search for the ArUco tag. We also define the number of steps for the sweep, then create the step size for the head pan joint.
```python
@ -262,7 +257,6 @@ self.min_tilt_position = -0.75
self.tilt_num_steps = 3
self.tilt_step_size = pi/16
```
Set the minimum position of the tilt joint, the number of steps, and the size of each step.
Assign *trajectory_goal* as a `FollowJointTrajectoryGoal` message type. Then extract the string value from the `joint` key. Also, assign *point* as a `JointTrajectoryPoint` message type.
```python
@ -307,14 +299,12 @@ if 'delta' in command:
new_value = joint_value + delta
point.positions = [new_value]
```
Check to see if `delta` is a key in the command dictionary. Then get the current position of the joint and add the delta as a a new position value.
```python
elif 'position' in command:
point.positions = [command['position']]
```
Check to see if `position`is a key in the command dictionary. Then extract the position value.
Then `trajectory_goal.trajectory.points` is defined by the positions set in *point*. Specify the coordinate frame that we want (*base_link*) and set the time to be now. Make the action call and send the goal. The last line of code waits for the result before it exits the python script.
Use a try-except block to look up the transform between the *base_link* and requested ArUco tag. Then publish and return the `TransformStamped` message.
Create a StaticTranformBoradcaster Node. Also, start a tf buffer that will store the tf information for a few seconds.Then set up a tf listener, which will subscribe to all of the relevant tf topics, and keep track of the information. Include `rospy.sleep(1.0)` to give the listener some time to accumulate transforms.
```python
@ -418,8 +401,4 @@ if __name__ == '__main__':
except KeyboardInterrupt:
rospy.loginfo('interrupt received, so shutting down')
```
Declare `LocateArUcoTag` object. Then run the `main()` method.
In this example, we will be utilizing the [move_base ROS node](http://wiki.ros.org/move_base), a component of the [ROS navigation stack](http://wiki.ros.org/navigation?distro=melodic) to send base goals to the Stretch robot.
## Build a map
First, begin by building a map of the space the robot will be navigating in. If you need a refresher on how to do this, then check out the [Navigation Stack tutorial](navigation_stack.md).
## Getting Started
Next, with your created map, we can navigate the robot around the mapped space. Run:
Where `${HELLO_FLEET_PATH}` is the path of the `<map_name>.yaml` file.
**IMPORTANT NOTE:** It's likely that the robot's location in the map does not match the robot's location in the real space. In the top bar of Rviz, use 2D Pose Estimate to lay an arrow down roughly where the robot is located in the real space. Below is a gif for reference.
<palign="center">
<imgsrc="images/2D_pose_estimate.gif"/>
</p>
Now we are going to use a node to send a a move base goal half a meter in front of the map's origin. run the following command to execute the [navigation.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/navigation.py) node.
```bash
# Terminal 2
cd catkin_ws/src/stretch_tutorials/src/
python3 navigation.py
```
### The Code
```python
#!/usr/bin/env python3
import rospy
import actionlib
import sys
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from geometry_msgs.msg import Quaternion
from tf import transformations
class StretchNavigation:
"""
A simple encapsulation of the navigation stack for a Stretch robot.
"""
def __init__(self):
"""
Create an instance of the simple navigation interface.
The done_callback function will be called when the joint action is complete.
:param self: The self reference.
:param status: status attribute from MoveBaseActionResult message.
:param result: result attribute from MoveBaseActionResult message.
"""
if status == actionlib.GoalStatus.SUCCEEDED:
rospy.loginfo('{0}: SUCCEEDED in reaching the goal.'.format(self.__class__.__name__))
else:
rospy.loginfo('{0}: FAILED in reaching the goal.'.format(self.__class__.__name__))
if __name__ == '__main__':
rospy.init_node('navigation', argv=sys.argv)
nav = StretchNavigation()
nav.go_to(0.5, 0.0, 0.0)
```
### The Code Explained
Now let's break the code down.
```python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
import actionlib
import sys
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from geometry_msgs.msg import Quaternion
from tf import transformations
```
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes).
rospy.loginfo('{0}: Made contact with move_base server'.format(self.__class__.__name__))
```
Set up a client for the navigation action. On the Stretch, this is called `move_base`, and has type `MoveBaseAction`. Once we make the client, we wait for the server to be ready.
```python
self.goal = MoveBaseGoal()
self.goal.target_pose.header.frame_id = 'map'
self.goal.target_pose.header.stamp = rospy.Time()
```
Make a goal for the action. Specify the coordinate frame that we want, in this instance the *map*. Then we set the time to be now.
```python
self.goal.target_pose.pose.position.x = 0.0
self.goal.target_pose.pose.position.y = 0.0
self.goal.target_pose.pose.position.z = 0.0
self.goal.target_pose.pose.orientation.x = 0.0
self.goal.target_pose.pose.orientation.y = 0.0
self.goal.target_pose.pose.orientation.z = 0.0
self.goal.target_pose.pose.orientation.w = 1.0
```
Initialize a position in the coordinate frame.
```python
def get_quaternion(self,theta):
"""
A function to build Quaternians from Euler angles. Since the Stretch only
rotates around z, we can zero out the other angles.
:param theta: The angle (radians) the robot makes with the x-axis.
The `MoveBaseGoal()` data structure has three goal positions (in meters), along each of the axes. For Stretch, it will only pay attention to the x and y coordinates, since it can't move in the z direction.
Send the goal and include the `done_callback()` function in one of the arguments in `send_goal()`.
```python
def done_callback(self, status, result):
"""
The done_callback function will be called when the joint action is complete.
:param self: The self reference.
:param status: status attribute from MoveBaseActionResult message.
:param result: result attribute from MoveBaseActionResult message.
"""
if status == actionlib.GoalStatus.SUCCEEDED:
rospy.loginfo('{0}: SUCCEEDED in reaching the goal.'.format(self.__class__.__name__))
else:
rospy.loginfo('{0}: FAILED in reaching the goal.'.format(self.__class__.__name__))
```
Conditional statement to print whether the goal status in the `MoveBaseActionResult` succeeded or failed.
```python
rospy.init_node('navigation', argv=sys.argv)
nav = StretchNavigation()
```
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Declare the `StretchNavigation` object.
```python
nav.go_to(0.5, 0.0, 0.0)
```
Send a move base goal half a meter in front of the map's origin.
@ -44,18 +44,18 @@ First, open a terminal and run the stretch driver launch file.
roslaunch stretch_core stretch_driver.launch
```
Then in a new terminal run the rplidar launch file from `stretch_core`.
Then in a new terminal run the `rplidar.launch` file from `stretch_core`.
```bash
# Terminal 2
roslaunch stretch_core rplidar.launch
```
To filter the lidar scans for ranges that are directly in front of Stretch (width of 1 meter) run the scan filter node by typing the following in a new terminal.
To filter the lidar scans for ranges that are directly in front of Stretch (width of 1 meter) run the [scan_filter.py](class="na">https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/scan_filter.py) node by typing the following in a new terminal.
```bash
# Terminal 3
cd catkin_ws/src/stretch_tutorials/src/
python scan_filter.py
python3 scan_filter.py
```
Then run the following command to bring up a simple RViz configuration of the Stretch robot.
@ -72,7 +72,7 @@ Change the topic name from the LaserScan display from */scan* to */filter_scan*.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
from numpy import linspace, inf
@ -80,24 +80,24 @@ from math import sin
from sensor_msgs.msg import LaserScan
class ScanFilter:
"""
A class that implements a LaserScan filter that removes all of the points
that are not infront of the robot.
"""
"""
A class that implements a LaserScan filter that removes all of the points
points = [r * sin(theta) if (theta <-2.5ortheta> 2.5) else inf for r,theta in zip(msg.ranges, angles)]
@ -116,9 +116,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
@ -127,7 +127,7 @@ from numpy import linspace, inf
from math import sin
from sensor_msgs.msg import LaserScan
```
You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus why linspace, inf, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe and publish LaserScan messages.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). There are functions from `numpy` and `math` that are required within this code, thus why linspace, inf, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe and publish `LaserScan` messages.
```python
self.width = 1
@ -138,12 +138,12 @@ We're going to assume that the robot is pointing up the x-axis, so that any poin
Set up a subscriber. We're going to subscribe to the topic *scan*, looking for LaserScan messages. When a message comes in, ROS is going to pass it to the function "callback" automatically.
Set up a subscriber. We're going to subscribe to the topic *scan*, looking for `LaserScan` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically.
`pub = rospy.Publisher("filtered_scan", LaserScan, queue_size=10)` declares that your node is publishing to the *filtered_scan* topic using the message type LaserScan. This lets the master tell any nodes listening on *filtered_scan* that we are going to publish data on that topic.
`pub = rospy.Publisher("filtered_scan", LaserScan, queue_size=10)` declares that your node is publishing to the *filtered_scan* topic using the message type `LaserScan`. This lets the master tell any nodes listening on *filtered_scan* that we are going to publish data on that topic.
@ -171,7 +171,7 @@ Substitute in the new ranges in the original message, and republish it.
rospy.init_node('scan_filter')
ScanFilter()
```
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate the class with `ScanFilter()`
@ -180,7 +180,4 @@ rospy.spin()
```
Give control to ROS. This will allow the callback to be called whenever new
messages come in. If we don't put this line in, then the node will not work,
and ROS will not process any messages.
**Previous Example:** [Teleoperate Stretch with a Node](example_1.md)
**Next Example:** [Mobile Base Collision Avoidance](example_3.md)
@ -14,13 +14,13 @@ Then in a new terminal type the following to activate the LiDAR sensor.
roslaunch stretch_core rplidar.launch
```
To set *navigation* mode and to activate the avoider node, type the following in a new terminal.
To set *navigation* mode and to activate the [avoider.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/avoider.py) node, type the following in a new terminal.
```bash
# Terminal 3
rosservice call /switch_to_navigation_mode
cd catkin_ws/src/stretch_tutorials/src/
python avoider.py
python3 avoider.py
```
To stop the node from sending twist messages, type **Ctrl** + **c** in the terminal running the avoider node.
@ -31,7 +31,7 @@ To stop the node from sending twist messages, type **Ctrl** + **c** in the termi
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
from numpy import linspace, inf, tanh
@ -66,9 +66,9 @@ class Avoider:
def set_speed(self,msg):
"""
Callback function to deal with incoming laserscan messages.
Callback function to deal with incoming LaserScan messages.
:param self: The self reference.
:param msg: The subscribed laserscan message.
:param msg: The subscribed LaserScan message.
:publishes self.twist: Twist message.
"""
@ -91,9 +91,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
@ -103,7 +103,7 @@ from math import sin
from geometry_msgs.msg import Twist
from sensor_msgs.msg import LaserScan
```
You need to import rospy if you are writing a ROS Node. There are functions from numpy and math that are required within this code, thus linspace, inf, tanh, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe to LaserScan messages. The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). There are functions from `numpy` and `math` that are required within this code, thus linspace, inf, tanh, and sin are imported. The `sensor_msgs.msg` import is so that we can subscribe to `LaserScan` messages. The `geometry_msgs.msg` import is so that we can send velocity commands to the robot.
points = [r * sin(theta) if (theta <-2.5ortheta> 2.5) else inf for r,theta in zip(msg.ranges, angles)]
new_ranges = [r if abs(y) <self.extentelseinfforr,yinzip(msg.ranges,points)]
```
This line of code utilizes linspace to compute each angle of the subscribed scan. Here we compute the y coordinates of the ranges that are below -2.5 and above 2.5 radians of the scan angles. These limits are sufficient for considering scan ranges in front of Stretch, but these values can be altered to your preference. If the absolute value of a point's y-coordinate is under self.extent then keep the range, otherwise use inf, which means "no return".
This line of code utilizes linspace to compute each angle of the subscribed scan. Here we compute the y coordinates of the ranges that are below -2.5 and above 2.5 radians of the scan angles. These limits are sufficient for considering scan ranges in front of Stretch, but these values can be altered to your preference. If the absolute value of a point's y-coordinate is under self.extent then keep the range, otherwise use inf, which means "no return".
```python
@ -167,11 +167,8 @@ rospy.init_node('avoider')
Avoider()
rospy.spin()
```
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate class with `Avioder()`
Give control to ROS with `rospy.spin()`. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
**Next Example:** [Give Stretch a Balloon](example_4.md)
Give control to ROS with `rospy.spin()`. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
the `rviz` flag will open an RViz window to visualize a variety of ROS topics. In a new terminal run the following commands to create a marker.
the `rviz` flag will open an RViz window to visualize a variety of ROS topics. In a new terminal run the following commands to execute the [marker.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/marker.py) node.
```bash
# Terminal 2
cd catkin_ws/src/stretch_tutorials/src/
python marker.py
python3 marker.py
```
The gif below demonstrates how to add a new *Marker* display type, and change the topic name from `visualization_marker` to `balloon`. A red sphere Marker should appear above the Stretch robot.
The gif below demonstrates how to add a new `Marker` display type, and change the topic name from */visualization_marker* to */balloon*. A red sphere Marker should appear above the Stretch robot.
<palign="center">
<imgsrc="images/balloon.gif"/>
@ -26,7 +24,7 @@ The gif below demonstrates how to add a new *Marker* display type, and change th
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
from visualization_msgs.msg import Marker
```
You need to import rospy if you are writing a ROS Node. Import the `Marker` type from the visualization_msgs.msg package. This import is required to publish a `Marker`, which will be visualized in RViz.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `Marker` type from the `visualization_msgs.msg` package. This import is required to publish a `Marker`, which will be visualized in RViz.
Create a maker. Markers of all shapes share a common type. Set the frame ID and type. The frame ID is the frame in which the position of the marker is specified. The type is the shape of the marker. Further details on marker shapes can be found here: [RViz Markers](http://wiki.ros.org/rviz/DisplayTypes/Marker)
Create a `Marker()` message type. Markers of all shapes share a common type. Set the frame ID and type. The frame ID is the frame in which the position of the marker is specified. The type is the shape of the marker. Further details on marker shapes can be found here: [RViz Markers](http://wiki.ros.org/rviz/DisplayTypes/Marker)
Specify the pose of the marker. Since spheres are rotationally invariant, we're only going to specify the positional elements. As usual, these are in the coordinate frame named in frame_id. In this case, the position will always be directly 2 meters above the frame_id (*base_link*), and will move with it.
Specify the pose of the marker. Since spheres are rotationally invariant, we're only going to specify the positional elements. As usual, these are in the coordinate frame named in `frame_id`. In this case, the position will always be directly 2 meters above the frame_id (*base_link*), and will move with it.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate class with `Balloon()`
@ -172,8 +166,4 @@ while not rospy.is_shutdown():
balloon.publish_marker()
rate.sleep()
```
This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check `is_shutdown()` to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop.
**Previous Example:** [Mobile Base Collision Avoidance](example_3.md)
This loop is a fairly standard rospy construct: checking the `rospy.is_shutdown()` flag and then doing work. You have to check `is_shutdown()` to check if your program should exit (e.g. if there is a **Ctrl-C** or otherwise). The loop calls `rate.sleep()`, which sleeps just long enough to maintain the desired rate through the loop.
@ -10,21 +10,19 @@ Begin by starting up the stretch driver launch file.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
You can then hit the run-stop button (you should hear a beep and the LED light in the button blink) and move the robot's joints to a desired configuration. Once you are satisfied with the configuration, hold the run-stop button until you hear a beep. Then run the following command to print the joint positions of the lift, arm, and wrist.
You can then hit the run-stop button (you should hear a beep and the LED light in the button blink) and move the robot's joints to a desired configuration. Once you are satisfied with the configuration, hold the run-stop button until you hear a beep. Then run the following command to excecute the [joint_state_printer.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/joint_state_printer.py) which will print the joint positions of the lift, arm, and wrist.
```bash
cd catkin_ws/src/stretch_tutorials/src/
python joint_state_printer.py
python3 joint_state_printer.py
```
Your terminal will output the `position` information of the previously mentioned joints shown below.
It's important to note that the arm has 4 prismatic joints and the sum of these positions gives the wrist extension distance. The wrist extension is needed when sending [joint trajectory commands](follow_joint_trajectory.md) to the robot. Here is an image of the arm joints for reference:
**IMPORTANT NOTE:** Stretch's arm has 4 prismatic joints and the sum of these positions gives the *wrist_extension* distance. The *wrist_extension* is needed when sending [joint trajectory commands](follow_joint_trajectory.md) to the robot. Further, you **can not** actuate an individual arm joint. Here is an image of the arm joints for reference:
<palign="center">
<imgsrc="images/joints.png"/>
@ -32,7 +30,7 @@ It's important to note that the arm has 4 prismatic joints and the sum of these
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
import sys
from sensor_msgs.msg import JointState
```
You need to import rospy if you are writing a ROS Node. Import `sensor_msgs.msg` so that we can subscribe to `JointState` messages.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import `sensor_msgs.msg` so that we can subscribe to `JointState` messages.
@ -108,20 +109,22 @@ Set up a subscriber. We're going to subscribe to the topic "*joint_states*", lo
def callback(self, msg):
self.joint_states = msg
```
This is the callback function where he JointState messages are stored as *self.joint_states*. Further information about the this message type can be found here: [JointState Message](http://docs.ros.org/en/lunar/api/sensor_msgs/html/msg/JointState.html)
This is the callback function where he `JointState` messages are stored as *self.joint_states*. Further information about the this message type can be found here: [JointState Message](http://docs.ros.org/en/lunar/api/sensor_msgs/html/msg/JointState.html)
```python
def print_states(self, joints):
joint_positions = []
```
This is the `print_states()` function which takes in a list of joints of interest as its argument. the is also an empty list set as *joint_positions* and this is where the positions of the requested joints will be appended.
In this section of the code, a forloop is used to parse the names of the requested joints from the *self.joint_states* list. The `index()` function returns the index a of the name of the requested joint and appends the respective position to our *joint_positions* list.
@ -129,31 +132,27 @@ In this section of the code, a forloop is used to parse the names of the request
rospy.signal_shutdown("done")
sys.exit(0)
```
The first line of code initiates a clean shutodwn of ROS. The second line of code exits the Python interpreter.
The first line of code initiates a clean shutdown of ROS. The second line of code exits the Python interpreter.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Declare object, *JSP*, from the `JointStatePublisher` class.
The use of the `rospy.sleep()` function is to allow the *JSP* class to initialize all of its features before requesting to publish joint positions of desired joints (running the `print_states()`function).
The use of the `rospy.sleep()` function is to allow the *JSP* class to initialize all of its features before requesting to publish joint positions of desired joints (running the `print_states()`method).
Create a list of the desired joints that you want positions to be printed. Then use that list as an argument for the `print_states()`function.
Create a list of the desired joints that you want positions to be printed. Then use that list as an argument for the `print_states()`method.
```python
rospy.spin()
```
Give control to ROS with `rospy.spin()`. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
**Previous Example** [Give Stretch a Balloon](example_4.md)
@ -6,28 +6,25 @@ In this example, we will review a Python script that prints out and stores the e
<imgsrc="images/effort_sensing.gif"/>
</p>
Begin by running the following command in the terminal in a terminal.
```bash
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *position* mode using a rosservice call. Then run the single effort sensing node.
Switch the mode to *position* mode using a rosservice call. Then run the [effort_sensing.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/effort_sensing.py) node.
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python effort_sensing.py
python3 effort_sensing.py
```
This will send a `FollowJointTrajectory` command to move Stretch's arm or head while also printing the effort of the lift.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import time
import actionlib
@ -81,7 +78,7 @@ class JointActuatorEffortSensor(hm.HelloNode):
rospy.loginfo('Sent position goal = {0}'.format(trajectory_goal))
self.trajectory_client.wait_for_result()
def feedback_callback(self,feedback):
@ -117,7 +114,7 @@ class JointActuatorEffortSensor(hm.HelloNode):
:param result: result attribute from FollowJointTrajectoryActionResult message.
"""
if status == actionlib.GoalStatus.SUCCEEDED:
rospy.loginfo('Suceeded')
rospy.loginfo('Succeeded')
else:
rospy.loginfo('Failed')
@ -153,9 +150,9 @@ if __name__ == '__main__':
This code is similar to that of the [multipoint_command](https://github.com/hello-robot/stretch_tutorials/blob/main/src/multipoint_command.py) and [joint_state_printer](https://github.com/hello-robot/stretch_tutorials/blob/main/src/joint_state_printer.py) node. Therefore, this example will highlight sections that are different from those tutorials. Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
@ -171,19 +168,18 @@ from trajectory_msgs.msg import JointTrajectoryPoint
from sensor_msgs.msg import JointState
import hello_helpers.hello_misc as hm
```
You need to import rospy if you are writing a ROS Node. Import the `FollowJointTrajectoryGoal` from the `control_msgs.msg` package to control the Stretch robot. Import `JointTrajectoryPoint` from the `trajectory_msgs` package to define robot trajectories. The `hello_helpers` package consists of a module that provides various Python scripts used across stretch_ros. In this instance, we are importing the `hello_misc` script.
You need to import rospy if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `FollowJointTrajectoryGoal` from the `control_msgs.msg` package to control the Stretch robot. Import `JointTrajectoryPoint` from the `trajectory_msgs` package to define robot trajectories. The `hello_helpers` package consists of a module that provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance, we are importing the `hello_misc` script.
```Python
class JointActuatorEffortSensor(hm.HelloNode):
"""
A class that sends multiple joint trajectory goals to a single joint.
"""
def __init__(self):
def __init__(self, export_data=False):
"""
Function that initializes the subscriber,and other features.
:param self: The self reference.
:param export_data: A boolean message type.
"""
hm.HelloNode.__init__(self)
```
@ -192,20 +188,19 @@ The `JointActuatorEffortSensor ` class inherits the `HelloNode` class from `hm`
Set up a subscriber. We're going to subscribe to the topic "*joint_states*", looking for `JointState` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically. Create a list of the desired joints you want to print.
Create an empty list to store the joint effort values. The *self.save_path* is the directory path where the .txt file of the effort values will be stored. You can change this path to a preferred directory. The *self.export_data* is a boolean and its default value is set to False. If set to True, then the joint values will be stored in a .txt file, otherwise, the values will be printed in the terminal where you ran the effort sensing node.
The feedback callback function takes in the `FollowJointTrajectoryActionFeedback` message as its argument.
```python
@ -226,7 +220,6 @@ if 'wrist_extension' in self.joints:
self.joints.remove('wrist_extension')
self.joints.append('joint_arm_l0')
```
Use a conditional statement to replace `wrist_extenstion` to `joint_arm_l0`. This is because `joint_arm_l0` has the effort values that the `wrist_extension` is experiencing.
:param result: result attribute from FollowJointTrajectoryActionResult message.
"""
```
The done callback function takes in the `FollowJointTrajectoryActionResult` messages as its arguments.
```python
if status == actionlib.GoalStatus.SUCCEEDED:
rospy.loginfo('Suceeded')
rospy.loginfo('Succeeded')
else:
rospy.loginfo('Failed')
```
Conditional statement to print whether the goal status in the `FollowJointTrajectoryActionResult` succeeded or failed.
```python
@ -281,7 +271,6 @@ if self.export_data:
writer.writerows(self.joint_effort)
```
A conditional statement is used to export the data to a .txt file. The file's name is set to the date and time the node was executed. That way, no previous files are overwritten.
@ -291,23 +280,17 @@ A conditional statement is used to export the data to a .txt file. The file's na
We added a simple python script, [stored_data_plotter.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/stored_data_plotter.py), to this package for plotting the stored data. Note you have to change the name of the file you wish to see in the python script. This is shown below:
We added a simple python script, [stored_data_plotter.py](https://github.com/hello-robot/stretch_tutorials/blob/main/src/stored_data_plotter.py), to this package for plotting the stored data. **Note** you have to change the name of the file you wish to see in the python script. This is shown below:
```Python
####################### Copy the file name here! #######################
file_name = '2022-06-30_11:26:20-AM'
```
Once you have changed the file name, then run the following in a new command.
```bash
cd catkin_ws/src/stretch_tutorials/src/
python stored_data_plotter.py
python3 stored_data_plotter.py
```
Because this is not a node, you don't need roscore to run this script. Please review the comments in the python script for additional guidance.
In this example, we will review the [image_view](http://wiki.ros.org/image_view?distro=melodic) ROS package and a Python script that captures an image from the RealSense camera.
In this example, we will review the [image_view](http://wiki.ros.org/image_view?distro=melodic) ROS package and a Python script that captures an image from the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/).
Begin by checking out the [feature/upright_camera_view](https://github.com/hello-robot/stretch_ros/tree/feature/upright_camera_view) branch in the stretch_ros repository. The configuration of the camera results in the images being displayed sideways. Thus, this branch publishes a new topic that rotates the raw image upright.
```bash
cd ~/catkin_ws/src/stretch_ros/stretch_core
git checkout feature/upright_camera_view
```
Then run the stretch driver launch file.
Begin by running the stretch `driver.launch` file.
```bash
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
To activate the RealSense camera and publish topics to be visualized, run the following launch file in a new terminal.
To activate the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/) and publish topics to be visualized, run the following launch file in a new terminal.
Within this tutorial package, there is an RViz config file with the topics for perception already in the Display tree. You can visualize these topics and the robot model by running the command below in a new terminal.
Then you can save the current image by right-clicking on the display window. By deafult, images will be saved as frame000.jpg, frame000.jpg, etc. Note, that the image will be saved to the terminal's current work directory.
**OPTION 2:** Use the `image_saver` node to save an image to the terminals current work directory.
In this section, you can use a Python node to capture an image from the RealSense camera. Run the following commands to save a .jpeg image of the image topic */camera/color/image_raw_upright_view*.
In this section, you can use a Python node to capture an image from the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/). Execute the [capture_image.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/capture_image.py) node to save a .jpeg image of the image topic */camera/color/image_raw_upright_view*.
```bash
# Terminal 4
cd ~/catkin_ws/src/stretch_tutorials/src
python capture_image.py
python3 capture_image.py
```
An image named **camera_image.jpeg** is saved in the **stored_data** folder in this package.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
@ -136,14 +120,12 @@ import sys
import os
import cv2
```
You need to import rospy if you are writing a ROS Node. There are functions from sys, os, and cv2 that are required within this code. cv2 is a library of Python functions that implements computer vision algorithms. Further information about cv2 can be found here: [OpenCV Python](https://www.geeksforgeeks.org/opencv-python-tutorial/).
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). There are functions from sys, os, and cv2 that are required within this code. cv2 is a library of Python functions that implements computer vision algorithms. Further information about cv2 can be found here: [OpenCV Python](https://www.geeksforgeeks.org/opencv-python-tutorial/).
```python
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
```
The `sensor_msgs.msg` is imported so that we can subscribe to ROS `Image` messages. Import [CvBridge](http://wiki.ros.org/cv_bridge) to convert between ROS `Image` messages and OpenCV images.
Join the directory and file name using the `path.join()` function. Then use the `imwrite()` function to save the image.
```python
rospy.signal_shutdown("done")
sys.exit(0)
```
The first line of code initiates a clean shutdown of ROS. The second line of code exits the Python interpreter.
```python
rospy.init_node('capture_image', argv=sys.argv)
CaptureImage()
```
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate the class with `CaptureImage()`
Instantiate the `CaptureImage()` class.
```python
rospy.spin()
```
Give control to ROS. This will allow the callback to be called whenever new
messages come in. If we don't put this line in, then the node will not work,
and ROS will not process any messages.
Give control to ROS. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
## Edge Detection
@ -214,9 +189,8 @@ In this section, we highlight a node that utilizes the [Canny Edge filter](https
```bash
# Terminal 4
cd ~/catkin_ws/src/stretch_tutorials/src
python edge_detection.py
python3 edge_detection.py
```
The node will publish a new Image topic named */image_edge_detection*. This can be visualized in RViz and a gif is provided below for reference.
<palign="center">
@ -225,7 +199,7 @@ The node will publish a new Image topic named */image_edge_detection*. This can
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import sys
@ -235,7 +209,6 @@ import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
class EdgeDetection:
"""
A class that converts a subscribed ROS image to a OpenCV image and saves
This example will showcase how to save the interpreted speech from Stretch's [ReSpeaker Mic Array v2.0](https://wiki.seeedstudio.com/ReSpeaker_Mic_Array_v2.0/) to a text file.
<palign="center">
<imgsrc="images/respeaker.jpg"/>
</p>
Begin by running the `sample_respeaker.launch` file in a terminal.
Begin by running the `respeaker.launch` file in a terminal.
```bash
# Terminal 1
roslaunch stretch_core respeaker.launch
roslaunch respeaker_ros sample_respeaker.launch
```
Then run the speech_text node.
Then run the [speech_text.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/speech_text.py) node.
```bash
# Terminal 2
cd catkin_ws/src/stretch_tutorials/src/
python speech_text.py
python3 speech_text.py
```
The ReSpeaker will be listening and will start to interpret speech and save the transcript to a text file. To stop shutdown the node, type **Ctrl** + **c** in the terminal.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import os
@ -42,7 +37,7 @@ class SpeechText:
Initialize subscriber and directory to save speech to text file.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
import os
```
You need to import rospy if you are writing a ROS Node.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes).
```python
from speech_recognition_msgs.msg import SpeechRecognitionCandidates
```
Import `SpeechRecognitionCandidates` from the `speech_recgonition_msgs.msg` so that we can receive the interpreted speech.
Set up a subscriber. We're going to subscribe to the topic "*speech_to_text*", looking for `SpeechRecognitionCandidates` messages. When a message comes in, ROS is going to pass it to the function "callback" automatically.
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker. NOTE: the name must be a base name, i.e. it cannot contain any slashes "/".
The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy the name of your node -- until rospy has this information, it cannot start communicating with the ROS Master. **NOTE:** the name must be a base name, i.e. it cannot contain any slashes "/".
Instantiate the class with `SpeechText()`
Instantiate the `SpeechText()` class.
```python
rospy.spin()
```
Give control to ROS. This will allow the callback to be called whenever new
messages come in. If we don't put this line in, then the node will not work,
@ -8,24 +8,22 @@ Begin by running the following command in a new terminal.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *position* mode using a rosservice call. Then run the `sample_respeaker.launch`.
Switch the mode to *position* mode using a rosservice call. Then run the `respeaker.launch` file.
```bash
# Terminal 2
rosservice call /switch_to_position_mode
roslaunch stretch_core respeaker.launch
```
Then run the voice teleoperation base node in a new terminal.
Then run the [voice_teleoperation_base.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/voice_teleoperation_base.py) node in a new terminal.
```bash
# Terminal 3
cd catkin_ws/src/stretch_tutorials/src/
python voice_teleoperation_base.py
python3 voice_teleoperation_base.py
```
In terminal 3, a menu of voice commands is printed. You can reference this menu layout below.
```
------------ VOICE TELEOP MENU ------------
@ -53,7 +51,7 @@ To stop the node from sending twist messages, type **Ctrl** + **c** or say "**qu
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import math
import rospy
@ -100,16 +98,17 @@ class GetVoiceCommands:
def callback_direction(self, msg):
"""
A callback function that converts the sound direction from degrees to radians.
A callback function that converts the incoming message, sound direction,
from degrees to radians.
:param self: The self reference.
:param msg: The Int32 message type.
:param msg: The Int32 message type that represents the sound direction.
A function that defines the teleoperation command based on the voice command.
:param self: The self reference.
:returns command: A dictionary type.
:returns command: A dictionary type that contains the type of base motion.
"""
command = None
if self.voice_command == 'forward':
@ -194,6 +193,7 @@ class VoiceTeleopNode(hm.HelloNode):
"""
A function that declares object from the GetVoiceCommands class, instantiates
the HelloNode class, and set the publishing rate.
:param self: The self reference.
"""
hm.HelloNode.__init__(self)
self.rate = 10.0
@ -251,26 +251,22 @@ class VoiceTeleopNode(hm.HelloNode):
self.send_command(command)
rate.sleep()
if __name__ == '__main__':
try:
node = VoiceTeleopNode()
node.main()
except KeyboardInterrupt:
rospy.loginfo('interrupt received, so shutting down')
```
### The Code Explained
This code is similar to that of the [multipoint_command](https://github.com/hello-robot/stretch_tutorials/blob/main/src/multipoint_command.py) and [joint_state_printer](https://github.com/hello-robot/stretch_tutorials/blob/main/src/joint_state_printer.py) node. Therefore, this example will highlight sections that are different from those tutorials. Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
```python
import math
import rospy
@ -283,10 +279,8 @@ from trajectory_msgs.msg import JointTrajectoryPoint
import hello_helpers.hello_misc as hm
from speech_recognition_msgs.msg import SpeechRecognitionCandidates
```
You need to import rospy if you are writing a ROS Node. Import the `FollowJointTrajectoryGoal` from the `control_msgs.msg` package to control the Stretch robot. Import `JointTrajectoryPoint` from the `trajectory_msgs` package to define robot trajectories. The `hello_helpers` package consists of a module that provides various Python scripts used across stretch_ros. In this instance, we are importing the `hello_misc` script. Import `sensor_msgs.msg` so that we can subscribe to JointState messages.
```python
class GetVoiceCommands:
```
@ -296,8 +290,7 @@ Create a class that subscribes to the speech to text recognition messages, print
self.step_size = 'medium'
self.rad_per_deg = math.pi/180.0
```
Set the default step size as medium and create a float value, self.rad_per_deg, to convert degrees to radians.
Set the default step size as medium and create a float value, *self.rad_per_deg*, to convert degrees to radians.
```python
self.small_deg = 5.0
@ -312,7 +305,6 @@ self.big_deg = 20.0
self.big_rad = self.rad_per_deg * self.big_deg
self.big_translate = 0.1
```
Define the three rotation and translation step sizes.
Initialize the voice command and sound direction to values that will not result in moving the base.
Set up two subscribers. The first one subscribes to the topic */speech_to_text*, looking for `SpeechRecognitionCandidates` messages. When a message comes in, ROS is going to pass it to the function `callback_speech` automatically. The second subscribes to */sound_direction* message and passes it to the `callback_direction` function.
The `callback_speech` stores the increment size for translational and rotational base motion to *inc*. The increment size is contingent on the *self.step_size* string value.
```python
@ -358,7 +346,6 @@ if self.voice_command == 'right':
In the `get_command()` function, the *command* is initialized as None, or set as a dictionary where the *joint* and *inc* values are stored. The *command* message type is dependent on the *self.voice_command* string value.
```python
@ -366,7 +353,6 @@ if (self.voice_command == "small") or (self.voice_command == "medium") or (self.
The `send_command` function stores the joint state message and uses a conditional statement to send joint trajectory goals. Also, assign *point* as a `JointTrajectoryPoint` message type.
Extract the joint name from the command dictionary.
```python
@ -431,27 +412,23 @@ inc = command['inc']
rospy.loginfo('inc = {0}'.format(inc))
new_value = inc
```
Extract the increment type from the command dictionary.
```python
point.positions = [new_value]
trajectory_goal.trajectory.points = [point]
```
Assign the new value position to the trajectory goal message type.
```python
self.trajectory_client.send_goal(trajectory_goal)
rospy.loginfo('Done sending command.')
```
Make the action call and send goal of the new joint position.
```python
self.speech.print_commands()
```
Reprint the voice command menu after the trajectory goal is sent.
```python
@ -466,9 +443,7 @@ def main(self):
rate = rospy.Rate(self.rate)
self.speech.print_commands()
```
The main function instantiates the HelloNode class, initializes the subscriber,
and call other methods in both the VoiceTeleopNode and GetVoiceCommands classes.
The main function instantiates the `HelloNode` class, initializes the subscriber, and call other methods in both the `VoiceTeleopNode` and `GetVoiceCommands` classes.
```python
while not rospy.is_shutdown():
@ -476,10 +451,8 @@ while not rospy.is_shutdown():
self.send_command(command)
rate.sleep()
```
Run a while loop to continuously check speech commands and send those commands to execute an action.
```python
try:
node = VoiceTeleopNode()
@ -487,7 +460,4 @@ try:
except KeyboardInterrupt:
rospy.loginfo('interrupt received, so shutting down')
```
Declare object from the VoiceTeleopNode class. Then execute the main() method/function.
**Previous Example** [Voice to Text](example_8.md)
**Next Example** [Tf2 Broadcaster and Listener](example_10.md)
Declare a `VoiceTeleopNode` object. Then execute the `main()` method.
@ -7,42 +7,27 @@ Stretch ROS driver offers a [`FollowJointTrajectory`](http://docs.ros.org/en/api
<imgsrc="images/stow_command.gif"/>
</p>
Begin by running the following command in the terminal in a terminal.
```bash
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *position* mode using a rosservice call. Then run the stow command node.
=== "Melodic"
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python stow_command.py
```
=== "Noetic"
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python3 stow_command.py
```
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python3 stow_command.py
```
This will send a `FollowJointTrajectory` command to stow Stretch's arm.
This will send a `FollowJointTrajectory` command to stow Stretch's arm.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
from control_msgs.msg import FollowJointTrajectoryGoal
@ -59,7 +44,7 @@ class StowCommand(hm.HelloNode):
def issue_stow_command(self):
'''
Function that makes an action call and sends stow postion goal.
Function that makes an action call and sends stow position goal.
:param self: The self reference.
'''
stow_point = JointTrajectoryPoint()
@ -100,10 +85,9 @@ if __name__ == '__main__':
Now let's break the code down.
```python
#!/usr/bin/env python
#!/usr/bin/env python3
```
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python3 script.
```python
import rospy
@ -112,11 +96,10 @@ from trajectory_msgs.msg import JointTrajectoryPoint
import hello_helpers.hello_misc as hm
import time
```
You need to import rospy if you are writing a ROS Node. Import the FollowJointTrajectoryGoal from the [control_msgs.msg](http://wiki.ros.org/control_msgs) package to control the Stretch robot. Import JointTrajectoryPoint from the [trajectory_msgs](http://wiki.ros.org/trajectory_msgs) package to define robot trajectories. The [hello_helpers](https://github.com/hello-robot/stretch_ros/tree/master/hello_helpers) package consists of a module the provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance we are importing the hello_misc script.
You need to import `rospy` if you are writing a ROS [Node](http://wiki.ros.org/Nodes). Import the `FollowJointTrajectoryGoal` from the [control_msgs.msg](http://wiki.ros.org/control_msgs) package to control the Stretch robot. Import `JointTrajectoryPoint` from the [trajectory_msgs](http://wiki.ros.org/trajectory_msgs) package to define robot trajectories. The [hello_helpers](https://github.com/hello-robot/stretch_ros/tree/master/hello_helpers) package consists of a module the provides various Python scripts used across [stretch_ros](https://github.com/hello-robot/stretch_ros). In this instance we are importing the `hello_misc` script.
```python
class StowCommand(hm.HelloNode):
def __init__(self):
hm.HelloNode.__init__(self)
```
@ -137,7 +120,7 @@ The `issue_stow_command()` is the name of the function that will stow Stretch's
Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` is defined by the positions set in *stow_point*. Specify the coordinate frame that we want (base_link) and set the time to be now.
Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` is defined by the positions set in *stow_point*. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
```python
self.trajectory_client.send_goal(trajectory_goal)
@ -153,7 +136,7 @@ def main(self):
self.issue_stow_command()
time.sleep(2)
```
Create a function, `main()`, to do all of the setup for the `hm.HelloNode` class and issue the stow command.
Create a funcion, `main()`, to do all of the setup the `hm.HelloNode` class and issue the stow command.
```python
if __name__ == '__main__':
@ -179,21 +162,19 @@ Begin by running the following command in the terminal in a terminal.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *position* mode using a rosservice call. Then run the multipoint command node.
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python multipoint_command.py
python3 multipoint_command.py
```
This will send a list of `JointTrajectoryPoint` message types to move Stretch's arm.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import time
@ -265,7 +246,7 @@ if __name__ == '__main__':
```
### 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.
Seeing that there are similarities between the multipoint and stow command nodes, we will only breakdown the different components of the `multipoint_command` node.
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.
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.
## Single Joint Actuator
@ -310,13 +291,10 @@ You can also actuate a single joint for the Stretch. Below are the list of joint
joint_lift: lower_limit = 0.15, upper_limit = 1.10 # in meters
wrist_extension: lower_limit = 0.00, upper_limit = 0.50 # in meters
joint_wrist_yaw: lower_limit = -1.75, upper_limit = 4.00 # in radians
joint_head_pan: lower_limit = -4.10, upper_limit = 1.60 # in radians
joint_head_pan: lower_limit = -2.80, upper_limit = 2.90 # in radians
joint_head_tilt: lower_limit = -1.60, upper_limit = 0.40 # in radians
joint_gripper_finger_left: lower_limit = -0.35, upper_limit = 0.165 # in radians
# INCLUDED JOINT IN MANIPULATION MODE
joint_mobile_base_translation: lower_limit = -0.50, upper_limit = 0.50 # in radians
# INCLUDED JOINTS IN POSITION MODE
translate_mobile_base: No lower or upper limit. Defined by a step size in meters
rotate_mobile_base: No lower or upper limit. Defined by a step size in radians
@ -329,25 +307,22 @@ Begin by running the following command in the terminal in a terminal.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
```
Switch the mode to *position* mode using a rosservice call. Then run the single joint actuator node.
```bash
# Terminal 2
rosservice call /switch_to_position_mode
cd catkin_ws/src/stretch_tutorials/src/
python single_joint_actuator.py
python3 single_joint_actuator.py
```
This will send a list of `JointTrajectoryPoint` message types to move Stretch's arm.
The joint, *joint_gripper_finger_left*, is only needed when actuating the gripper.
### The Code
```python
#!/usr/bin/env python
#!/usr/bin/env python3
import rospy
import time
@ -404,7 +379,7 @@ if __name__ == '__main__':
```
### The Code Explained
Since the code is quite similar to the multipoint_command code, we will only review the parts that differ.
Since the code is quite similar to the `multipoint_command` code, we will only review the parts that differ.
Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` set by your list of points. Specify the coordinate frame that we want (base_link) and set the time to be now.
**Next Tutorial:** [Perception](perception.md)
Set *trajectory_goal* as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` set by your list of points. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
If you cannot dual boot and install ubuntu on your local machine, an alternative is to use [AWS RoboMaker](https://aws.amazon.com/robomaker/). AWS RoboMaker extends the ROS framework with cloud services. The service provides a robotics simulation service, allowing for testing the Stretch RE1 platform. If you are a first-time user of AWS RoboMaker, follow the [guide here](https://github.com/aws-robotics/aws-robomaker-robotics-curriculum/blob/main/getting-started-with-aws-robomaker/_modules/mod-2a-aws.md) to get up and running with the service.
If you cannot dual boot and install ubuntu on your local machine, an alternative is to use [AWS RoboMaker](https://aws.amazon.com/robomaker/). AWS RoboMaker extends the ROS framework with cloud services. The service provides a robotics simulation service, allowing for testing the Stretch RE1 platform. If you are a first-time user of AWS RoboMaker, follow the [guide here](https://github.com/aws-robotics/aws-robomaker-robotics-curriculum/blob/main/getting-started-with-aws-robomaker/_modules/mod-2a-aws.md) to get up and running with the service.
The graph allows a user to observe and affirm if topics are broadcasted to the correct nodes. This method can also be utilized to debug communication issues.
**Next Tutorial:** [RViz Basics](rviz_basics.md)
The graph allows a user to observe and affirm if topics are broadcasted to the correct nodes. This method can also be utilized to debug communication issues.
The Stretch robot is equipped with the Intel RealSense D435i camera, an essential component that allows the robot to measure and analyze the world around it. In this tutorial, we are going to showcase how to visualize the various topics published from the camera.
The Stretch robot is equipped with the [Intel RealSense D435i camera](https://www.intelrealsense.com/depth-camera-d435i/), an essential component that allows the robot to measure and analyze the world around it. In this tutorial, we are going to showcase how to visualize the various topics published from the camera.
Begin by checking out the [feature/upright_camera_view](https://github.com/hello-robot/stretch_ros/tree/feature/upright_camera_view) branch in the stretch_ros repository. The configuration of the camera results in the images being displayed sideways. Thus, this branch publishes a new topic that rotates the raw image upright.
Begin by checking out the [feature/upright_camera_view](https://github.com/hello-robot/stretch_ros/tree/feature/upright_camera_view) branch in the [stretch_ros](https://github.com/hello-robot/stretch_ros) repository. The configuration of the camera results in the images being displayed sideways. Thus, this branch publishes a new topic that rotates the raw image upright.
```bash
cd ~/catkin_ws/src/stretch_ros/stretch_core
@ -15,7 +15,7 @@ Then run the stretch driver launch file.
roslaunch stretch_core stretch_driver.launch
```
To activate the RealSense camera and publish topics to be visualized, run the following launch file in a new terminal.
To activate the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/) and publish topics to be visualized, run the following launch file in a new terminal.
```bash
# Terminal 2
@ -60,7 +60,4 @@ The `DepthCloud` display is visualized in the main RViz window. This display tak
## Deep Perception
Hello Robot also has a ROS package that uses deep learning models for various detection demos. A link to the package is provided: [stretch_deep_perception](https://github.com/hello-robot/stretch_ros/tree/master/stretch_deep_perception).
Hello Robot also has a ROS package that uses deep learning models for various detection demos. A link to the package is provided: [stretch_deep_perception](https://github.com/hello-robot/stretch_ros/tree/master/stretch_deep_perception).
Note that the teleop_twist_joy package has a deadman switch by default which disables the drive commands to be published unless pressed. For a Logitech F310 joystick, this button is A.
**Next Tutorial:** [Internal State of Stretch](internal_state_of_stretch.md)
Note that the teleop_twist_joy package has a deadman switch by default which disables the drive commands to be published unless pressed. For a Logitech F310 joystick, this button is A.