at_sonde_ros_driver

A ROS 2 driver to stream the monitored parameters of an In-Situ Aqua TROLL Multiparameter Sonde.

README

at_sonde_ros_driver

ROS Industrial CI

Jenkins Build Jazzy Bin Humble Bin

Rolling Devel Jazzy Devel Humble Devel

ROS Package Index Rolling ROS Package Index Jazzy ROS Package Index Humble

Overview

This package provides a ROS 2 driver to stream the monitored parameters of an In-Situ Aqua TROLL Multiparameter Sonde, through modbus serial communication.

This package has been tested with the AT600 Sonde.

Installation

Make sure you have ROS 2 installed on your system.

Binary

To install the binary package, use the following command:

sudo apt update
sudo apt install ros-$ROS_DISTRO-at-sonde-ros-driver

From Source

To build the package from source, follow these steps:

  1. Create a workspace directory:

mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
  1. Clone the repository:

git clone https://github.com/ma-shangao/at_sonde_ros_driver.git
  1. Prepare the required dependencies with rosdep:

cd ~/ros2_ws
rosdep install --from-paths src --ignore-src -r -y
  1. Build the package:

colcon build

ROS 2 Node: at_sonde_ros_driver_node

Published Topics

The node publishes the following topics:

Topic Name

Message Type

Description

see ROS param pub_topic_names

std_msgs/msg/Float32

Publisher of selected sonde parameters

ROS Parameters

The configurable ROS parameters for the node:

Parameter Name

Type

Default Value

Description

baud

int

19200

Baud rate for serial communication

modbus_debug_flag

bool

false

Enable debug messages for modbus communication

modbus_timeout_microseconds

int

700000

Timeout for modbus communication in microseconds

modbus_timeout_seconds

int

0

Timeout for modbus communication in seconds

pub_topic_names

list[string]

[“temperature”, “battery_remaining”]

Names of the topics to publish the streamed data

retry_limit

int

5

Number of retries for modbus communication

sensor_scan_flag

bool

false

Scan the sensor on the first use after reconfiguration

serial_port

string

“/dev/ttyUSB0”

Serial port for modbus communication

sonde_add

int

1

Sonde address for modbus communication

streaming_param_reg_adds

list[int]

[5450, 5674]

Register addresses of the parameters to be streamed

The pub_topic_names and streaming_param_reg_adds parameters must be set in pairs. The first element of pub_topic_names corresponds to the first element of streaming_param_reg_adds, and so on.

Usage

To run the node, use the following command:

ros2 run at_sonde_ros_driver at_sonde_ros_driver_node

The ROS parameters can also be configured using a YAML file.

ros2 run at_sonde_ros_driver at_sonde_ros_driver_node --ros-args --params-file <path_to_yaml_file>

Known Issues

Some ROS 2 parameters can currently only be set at the start of the node.