toposens_sync Documentation

Overview

ROS package for simultaneous use of multiple TS3 devices in a sensor system. It administers the lifecycle and ultrasonic emission characteristics of each sensor to coordinate incoming datastreams. It is designed as a thin layer for handling multiple toposens_driver::Sensor instances that individually encapsulate all the device communication and logic flow.

This tutorial describes the usage of two TS3 sensors. The described processes can also be applied to multiple sensors. It is assumed that you have already completed the tutorial for building the toposens stack and enabling serial port permissions.

Developed and tested for ROS Melodic on Ubuntu 18.04 (Bionic) and ROS Kinetic on Ubuntu 16.04 (Xenial) using Toposens TS3 ultrasonic sensor.

1. Setup

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.

2. Build Driver

Clone the toposens metapackage into your catkin workspace:

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

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

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

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

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

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

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.

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.

In order to visualize the pointcloud, RViz is launched.

5. Visualize Data

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).



toposens_sync
Author(s): Sebastian Dengler, Christopher Lang
autogenerated on Sun Feb 14 2021 03:20:30