toposens: toposens_bringup | toposens_description | toposens_driver | toposens_echo_driver | toposens_markers | toposens_msgs | toposens_pointcloud | toposens_sync

Package Summary

ROS device driver for communication with TS ECHO sensors on a CAN bus

toposens: toposens_bringup | toposens_description | toposens_driver | toposens_echo_driver | toposens_markers | toposens_msgs | toposens_pointcloud | toposens_sync

Package Summary

ROS device driver for communication with TS ECHO sensors on a CAN bus

Overview

This package contains nodes to enable the use of Toposens ECHO ONE sensor within ROS. Data will be published as toposens_msgs/TsScan.

ROS Nodes

toposens_echo_driver_node

Communicates with the Toposens Sensor Library and publishes ECHO ONE point clouds as toposens_msgs/TsScan.

Published Topics

ts_scans (toposens_msgs/TsScan)
  • Point cloud with additional header information and XYZIC points (x, y, z, intensity, confidence).

Parameters

~com_interface (std_msgs/String)
  • whether to use CAN or UART connection for ECHO ONE
~can_device (std_msgs/String)
  • CAN interface to use
~uart_device (std_msgs/String)
  • UART port to use
~loop_rate (double)
  • Spin rate of the ros node (for single shot mode)
~scans_topic (std_msgs/String)
  • Topic to publish point cloud to.
~sensor_mode (std_msgs/String)
  • Run the sensor in single-shot or continuous mode (options: [single_shot, continuous]).
~frame_id (std_msgs/String)
  • Base frame ID in which the data is published.
~target_frame (std_msgs/String)
  • Point cloud will be published with this prefix (e.g. toposens_ + sensor ID)
~wait_for_transform (double)
  • Wait until transforms are available.
~drop_single_sensor_transform_id (bool)
  • When using single sensor the ID can be omitted in the published transform between sensor-frame and toposens-base-link
~respawn (bool)
  • Restart node again if it crashes.
~write_cfg_to_sensor (bool)
  • Configure the sensor at startup with values from the parameter yaml file.
~transducer/volume (int)
  • Transducer amplitude (percentage)
~transducer/num_pulses (int)
  • Electrical pulses that the piezo transmitter is stimulated with in every transmission cycle.
~transducer/transducer_noise_threshold (double)
  • Threshold to filter noise during signal processing on sensor.
~transducer/transducer_noise_ratio (int)
  • Deprecated filter on sensor to determine echo quality. Set to 100 to disable.
~signal_processing/temperature (double)
  • Environment temperature used for speed of sound calculations.
~sensor/slp_dur_pulses (double)
  • Adds sleep after each measurement in ROS node. [experimental]
~sensor/near_field_enabled (bool)
  • Activate the sensor's near field detection. [experimental]
~sensor/near_field_threshold_phase_deviations (double)
  • Parameter for near field detection. [experimental]
~sensor/noise_threshold (int)
  • Mark frames as noisy based on sensor noise level. [experimental]
~sensor/enable_auto_gain (bool)
  • Dynamically adjust signal amplification to avoid clipping or too quiet echoes.

request_adc_dump

Service to request adc dump from sensor.

Parameters

sensor_id (std_msgs/String)
  • ID of the sensor to request the dump from.
file_path (std_msgs/String)
  • File path to save the ADC dump to.

Wiki: toposens_echo_driver (last edited 2022-05-11 12:50:26 by DennisMaier)