[Documentation] [TitleIndex] [WordIndex

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Multiple TS3 Sensors

Description: Using the toposens_sync package for synchronizing multiple TS3 sensors

Keywords: Toposens, TS3, ultrasound

Tutorial Level: INTERMEDIATE

It is assumed that the previous tutorial for building the toposens stack and enabling serial port permissions was completed already.

This tutorial describes the usage of two TS3 sensors. The described processes can also be applied to multiple sensors.

Connect the TS3 Sensors

Connect the two TS3 sensors via FTDI cables to any available USB ports on your computer. Obtain the connected terminal IDs for the devices (see previous tutorial).

Attach the sensors to a stable mount and measure the coordinates of their sensor frames relative to a desired reference frame.

Create a Launchfile

Create a launch file with the following content:

   1 <launch>
   2   <arg name="ports" default="[/dev/ttyUSB0, /dev/ttyUSB1]"/>
   3   <arg name="frame_ids" default="[ts3_1, ts3_2]"/>
   4 
   5   <node pkg="toposens_sync" type="toposens_sync_node"
   6         name="ts_sync_node" output="screen">
   7     <rosparam param="ports" subst_value="true">$(arg ports)</rosparam>
   8     <rosparam param="frames" subst_value="true">$(arg frame_ids)</rosparam>
   9   </node>
  10 
  11   <node pkg="tf" type="static_transform_publisher" name="toposens_link_1"
  12         args="0 -0.10 0 0 0 0 1 toposens ts3_1 100" />
  13   <node pkg="tf" type="static_transform_publisher" name="toposens_link_2"
  14         args="0 0.10 0 0 0 0 1 toposens ts3_2 100" />
  15 
  16   <node pkg="toposens_pointcloud" type="toposens_pointcloud_node"
  17         name="ts_cloud_node" output="screen">
  18     <param name="target_frame" value="toposens" />
  19   </node>
  20 
  21   <node pkg="rviz" type="rviz" name="grid_visualization" output="screen"
  22         args="-d $(find toposens_pointcloud)/rviz/toposens_pointcloud.rviz" />
  23 </launch>

The file can be broken down into the following parts:

   2   <arg name="ports" default="[/dev/ttyUSB0, /dev/ttyUSB1]"/>
   3   <arg name="frame_ids" default="[ts3_1, ts3_2]"/>

The terminal IDs ("ports") and frame IDs ("frame_ids") are defined as arrays. Both these arrays need to have the same size. Element [i] of "ports" is mapped to element [i] of "frame_ids".

   5   <node pkg="toposens_sync" type="toposens_sync_node"
   6         name="ts_sync_node" output="screen">
   7     <rosparam param="ports" subst_value="true">$(arg ports)</rosparam>
   8     <rosparam param="frames" subst_value="true">$(arg frame_ids)</rosparam>
   9   </node>

The ts_sync_node must be given the arrays of the terminal IDs and frame IDs as launch arguments. The ts_sync_node handles the alternating triggering of the sensors as well as the polling of their data stream.

  11   <node pkg="tf" type="static_transform_publisher" name="toposens_link_1"
  12         args="0 -0.10 0 0 0 0 1 toposens ts3_1 100" />
  13   <node pkg="tf" type="static_transform_publisher" name="toposens_link_2"
  14         args="0 0.10 0 0 0 0 1 toposens ts3_2 100" />

In order to set the transformation from the individual sensor frames (here: ts_1, ts_2) to the desired reference frame (here: toposens), static transform publishers are used. Fill in the correct tf parameters for your setup.

  16   <node pkg="toposens_pointcloud" type="toposens_pointcloud_node"
  17         name="ts_cloud_node" output="screen">
  18     <param name="target_frame" value="toposens" />
  19   </node>

The data that is accumulated from the two sensors can be translated into messages of type sensor_msgs/PointCloud2 via the ts_cloud_node. The name of the frame in which the pointcloud is published is given to the node as a launch argument.

  21   <node pkg="rviz" type="rviz" name="grid_visualization" output="screen"
  22         args="-d $(find toposens_pointcloud)/rviz/toposens_pointcloud.rviz" />

In order to visualize the pointcloud, RViz is launched.

View Pointcloud

In order to visualize the data as sensor_msgs/PointCloud2 messages, launch the ts_sync_node as well as the ts_cloud_node with the created launch file. The firmware parameters for each TS3 sensor can be adjusted independently through rqt_reconfigure (see previous tutorial).


2019-10-19 13:16