@ -8,15 +8,12 @@ Begin by starting up the stretch driver launch file.
# Terminal 1
# Terminal 1
roslaunch stretch_core stretch_driver.launch
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://wiki.seeedstudio.com/ReSpeaker_Mic_Array_v2.0/) and publish topics to be visualized, run the following launch file in a new terminal.
@ -24,14 +21,12 @@ Then run the `PointCloud` transformer node.
cd catkin_ws/src/stretch_tutorials/src/
cd catkin_ws/src/stretch_tutorials/src/
python3 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.
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.
The gif below visualizes what happens when running the previous node.
The gif below visualizes what happens when running the previous node.
<palign="center">
<palign="center">
@ -136,8 +131,7 @@ from sensor_msgs.msg import PointCloud2, PointCloud
from geometry_msgs.msg import Point32
from geometry_msgs.msg import Point32
from std_msgs.msg import Header
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`.
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.
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
```python
@ -172,20 +164,17 @@ The callback function that stores the the `PointCloud2` message.
temp_cloud = PointCloud()
temp_cloud = PointCloud()
temp_cloud.header = self.pcl2_cloud.header
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
```python
for data in pc2.read_points(self.pcl2_cloud, skip_nans=True):
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.
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
```python
rate = rospy.Rate(1)
rate = rospy.Rate(1)
rospy.sleep(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).
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
```python
# Run while loop until the node is shutdown
while not rospy.is_shutdown():
while not rospy.is_shutdown():
# Run the pcl_transformer method
PCT.pcl_transformer()
PCT.pcl_transformer()
rate.sleep()
rate.sleep()
```
```
Run a while loop until the node is shutdown. Within the while loop run the `pcl_transformer()` method.
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)
**Previous Example** [Tf2 Broadcaster and Listener](example_10.md)
**Next Example** [ArUco Tag Locator](example_12.md)