Size: 13950
Comment:
|
Size: 13594
Comment:
|
Deletions are marked like this. | Additions are marked like this. |
Line 19: | Line 19: |
## next.0.link=[[toposens/Tutorials/Using Multiple TS3 Sensors|Using Multiple TS3 Sensors]] ## next.1.link=[[toposens/Tutorials/Use a TS3 Sensor for Mapping with a TurtleBot3|Use a TS3 Sensor for Mapping with a TurteBot3]] ## next.2.link=[[toposens/Tutorials/Getting Started with the TS3 on a Raspberry Pi|Getting Started with the TS3 on a Raspberry Pi]] |
![]() |
Getting Started with ECHO ONE
Description: Using the Toposens stack to connect to and display data from Toposens 3D ultrasonic sensorsKeywords: Toposens, ECHO ONE, TS3, ultrasound
Tutorial Level: BEGINNER
Contents
This tutorial assumes that either Ubuntu 18.04 with ROS Melodic or Ubuntu 20.04 with ROS Noetic is used.
Install Driver
We provide three different ways of installing the Toposens ROS Software Stack. In the following we provide the details of how to set up each of those.
Docker Image from DockerHub
For the purpose of conveniently running the Toposens application we provide Docker images. This allows execution of the toposens ROS-Stack without any ROS installation, package installation or compiling being necessary. (Tested with Ubuntu 20.04 focal)
As a requirement, you need to have Docker installed on your system: https://www.docker.com/.
The Docker runtime images can be pulled and run from https://hub.docker.com/u/toposens as follows: (Make sure to have your Toposens sensor connected to the given port)
# Headless mode ECHO ONE: $ docker run -it --net=host --env DRIVER=ECHO_ONE --env COM_INTERFACE=CAN --env GUI_ENABLE=false --cap-add=NET_ADMIN --env USER=toposens toposens/noetic # Headless mode TS3: $ docker run --device=/dev/ttyUSB0 -it --env GUI_ENABLE=false --env DRIVER=TS3 --env COM_INTERFACE=UART --net=host --env USER=toposens toposens/noetic # Execution with RViz GUI ECHO ONE: $ xhost +local:root; docker run -it --env="DISPLAY" --env="QT_X11_NO_MITSHM=1" --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" --env GUI_ENABLE=true --cap-add=NET_ADMIN --env DRIVER=ECHO_ONE --env COM_INTERFACE=CAN --net=host --env USER=toposens --privileged toposens/noetic; xhost -local:root # Execution with RViz GUI TS3: $ xhost +local:root; docker run --device=/dev/ttyUSB0 -it --env="DISPLAY" --env="QT_X11_NO_MITSHM=1" --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" --env GUI_ENABLE=true --env DRIVER=TS3 --env COM_INTERFACE=UART --net=host --env USER=toposens --privileged toposens/noetic; xhost -local:root
Install Binaries from Ubuntu Repository
Depending on the ROS distribution that you are using, install the binaries of the Toposens ROS packages with the following command:
sudo apt install ros-<distro>-toposens
E.g. if you are using ROS Noetic, it would look like this:
sudo apt install ros-noetic-toposens
Build Driver from Source
As an alternative to installing the binaries, you could also compile the packages from source. In order to follow the steps below, you need to have a catkin workspace and catkin tools installed. Check these links if you need assistance in doing so:
Catkin tools installation (Note that the package for Noetic is python3-catkin-tools, and you might also need to install pip3 install osrf-pycommon)
Catkin workspace initialization, in the following we assume the workspace to be at ~/catkin_ws/
Then you are ready to clone the toposens metapackage into the source folder of your catkin workspace:
cd ~/catkin_ws/src git clone --recurse-submodules https://gitlab.com/toposens/public/ros-packages.git
Use rosdep to install missing dependencies:
rosdep init rosdep update rosdep install -y --from-paths ~/catkin_ws/src/ros-packages/ --ignore-src
In your catkin workspace build the package by using catkin build:
cd ~/catkin_ws catkin build toposens
Source your build space:
source ~/catkin_ws/devel/setup.bash
This needs to be done in every new terminal or you can add this command to your bashrc for it to be executed automatically when opening a new terminal window.
Enable Serial Port Permissions
Add yourself to the “dialout” group:
sudo adduser $USER dialout
Trigger updated group permissions to take effect:
newgrp dialout
Re-login or reboot for the updated group permissions to take effect permanently.
Connect ECHO ONE Sensor with CAN
The README of the toposens_echo_driver package provides instructions on how to enable the CAN interface for Ubuntu to be used with ROS.
Connect TS3 Sensor
Connect your Toposens TS3 sensor via the provided USB cable (for TS3 versions v1.0 & v1.1: FTDI cable) to any available USB port on your computer.
Obtain the connected terminal ID for the device:
dmesg | grep "cp210x" | tail -n 1 | awk 'NF{print $NF}'
For TS3 v1.0 & v1.1:
dmesg | grep "FTDI" | tail -n 1 | awk 'NF{print $NF}'
In the case below, the terminal ID would be ttyUSB0
Visualize Data
There are three different ways of viewing the data output from a TS3 sensor, which are published to three separate topics:
/ts_scans broadcasts messages of type toposens_msgs/TsScan, which hold the raw data stream parsed as toposens_msgs
/ts_markers broadcasts messages of type visualization_msgs/MarkerArray for simple visualization with RViz
/ts_cloud broadcasts messages of type sensor_msgs/PointCloud2, which can be visualized in RViz and also logged to a file
The utility of these topics is further explored in the following sections.
View Raw Stream
The ts_driver_node translates the sensor data into custom toposens_msgs/TsScan messages.
Launch the driver node to read data from ECHO ONE or TS3. If the interface/port obtained in the previous step is the default (can0 for ECHO ONE, /dev/ttyUSB0 for TS3), then the launch argument can be omitted:
roslaunch toposens_echo_driver driver.launch can_device:=can0
roslaunch toposens_driver ts3_driver.launch port:=/dev/ttyUSB0
The sensor data is published to the the topic /ts_scans. View the incoming scans with:
rostopic echo /ts_scans
Visualize Data as Markers
The ts_markers_node translates the messages of type toposens_msgs/TsScan into messages of type visualization_msgs/MarkerArray, which can be visualized in RViz.
The driver node as well as the markers node are launched from within one launch-file:
roslaunch toposens_bringup ts3.launch port:=/dev/ttyUSB0 use_markers:=true
The markers are visualized in RViz:
View Pointcloud in RViz
The ts_cloud_node translates the messages of type toposens_msgs/TsScan into messages of type sensor_msgs/PointCloud2.
||<#FFFFCC>Since version 2.0 the package makes use of the standard PointCloud type PointXYZINormal instead of the custom type TsPoint. As a result the PointCloud also contains information about the surface normals.||
Due to the specular reflection behavior of ultrasound, the surface normal of the detected object can be represented by a vector pointing from the detected point towards the sensor’s position while the point was recorded. This normal vector is added to the PointCloud representation. For a more detailed explanation of the physics behind Toposens sensors see Physics of 3D Ultrasonic Sensors.
The driver node as well as the pointcloud node are launched from within one launch-file (as before, port defaults to /dev/ttyUSB0 and can be omitted in this case):
roslaunch toposens_bringup echo_one.launch can_device:=can0
roslaunch toposens_bringup ts3.launch port:=/dev/ttyUSB0
For also launching rqt_reconfigure set the launch argument:
roslaunch toposens_bringup <sensor_launchfile> <launch_args> launch_rqt_reconfigure:=true
The pointcloud is visualized in RViz:
In order to visualize the surface normal vectors, run the launch-file with the corresponding argument:
roslaunch toposens_bringup ts3.launch lifetime_normals_vis:=1.0
Be aware that in case of a static sensor (i.e. no tf information) the normal vectors are simply pointing towards the sensor at any time.
The pointcloud is logged to the file /home/<user>/.ros/toposens.pcd. A different path can be given in the launch argument pcd_path. Note: This feature is experimental, and may result in processing issues when running the node for a long time.
Manipulate Parameters
To manipulate sensor parameters as well as visualization parameters live in realtime, run in an additional terminal window:
rosrun rqt_reconfigure rqt_reconfigure
The ts_driver_node respectively ts_markers_node need to be running for this to work.
Sensor Parameters
There are 6 different parameters that can be changed in the ts_driver_node.
Variable Name |
Description |
num_pulses |
This is the only parameter that has an effect on the emitted ultrasonic signal. It defines the number of electrical pulses that the piezo transmitter is stimulated with in every transmission cycle. The higher the number, the louder and longer the emitted signal will be. As a result, increasing the value will detect objects that are further away, decreasing it will increase the sensor's precision in short range. |
echo_rejection_threshold |
This parameter defines the minimum amplitude, i.e. the signal strength, that a received echo signal needs to have in order to be utilized for further processing. Signals that are below this threshold are discarded. As a result, increasing the value will ignore more points of smaller intensity and only allow strong reflectors to be detected. |
peak_detection_window |
This parameter defines the kernel size for a peak detection filter that is applied on the received ADC signals in order to find the peaks that link to the echoes of the detected objects. When it is set too high, objects that are close to each other might merge to one bigger object. Decreasing it might separate these objects but might also destabilize the resulting signal. |
noise_indicator_threshold |
This parameter has no effect on the visualization of the pointcloud or the markers. It is solely used to mark individual scans with a noise flag. This is done by calculating an overall noise level for the raw ADC signal of one frame. If this noise level lies above the noise_indicator_threshold, the noise flag for this scan is set. This might indicate that there are sources of ultrasonic disturbances in the scene. However the scans will be shown regardless of the noise flag. |
external_temperature |
This parameter defines the temperature that is used for calculating the speed to sound. Its accuracy has an effect on the correct calculation of the distance of objects. The value is only used if use_external_temperature is checked. |
use_external_temperature |
The TS3 also has an on-board temperature sensor. If use_external_temperature is not checked, the TS3 will use its on-board temperature sensor for speed-of-sound calculation. If it is checked, it will use the external_temperature. |
Marker Parameters
There are 2 parameters that can be changed in the ts_markers_node.
Variable Name |
Description |
lifetime |
Duration for which a marker should remain visible |
scale |
Magnitude for resizing markers equally and simultaneously |