Skip to content

3.1 rosserial

John-Paul Chouery edited this page Jan 31, 2025 · 3 revisions

Introduction to ROSSerial

ROSSerial is a protocol that enables microcontrollers to communicate with a ROS (Robot Operating System) environment. It is particularly useful in ROS 1 setups where hardware interacts with the software running on a Linux system. While ROS 1 will reach its end-of-life (EOL) on May 31, 2025, many projects, including the software found in the AUV-2025 repo, still rely on it. Maintaining ROS 1 code remains essential until a full transition to ROS 2 is complete.

Personal Recommendation

Avoid using custom ROS 1 messages whenever possible. They can cause synchronization issues with the ROS 1 library on platforms like the Jetson.

Setting Up ROSSerial Library

To use ROSSerial, you first need to generate the ROSSerial library for Arduino. On the Jetson, run:

rosrun rosserial_arduino make_libraries.py .

Once the library is generated, copy it to the Arduino libraries folder. For the AUV-Embedded-2025 repository, the library is already placed in the lib folder for the PlatformIO (PIO) workspace. Leads will update it as needed.

Writing ROSSerial Code

Preparing Your Code

Before integrating ROSSerial, ensure your code functions as expected using the serial monitor. Remove all debugging code such as Serial.println once the functionality is verified.

Including Necessary Libraries

To begin, include the ROSSerial library:

#include <ros.h>

Include the messages you will use. For example:

  • Custom message:

    #include <auv_msgs/ThrusterMicroseconds.h>
  • Standard message:

    #include <std_msgs/Float32.h>

Declaring Messages

Declare the messages you plan to publish or subscribe to:

std_msgs::Float32 batt1_voltage_msg;
std_msgs::Float32 batt2_voltage_msg;

Callback Functions for Subscribers

Define callback functions to handle subscribed messages:

void commandCb(const auv_msgs::ThrusterMicroseconds &tc) {
    memcpy(microseconds, tc.microseconds, 8 * sizeof(uint16_t));
}

Callbacks are fast and non-blocking. It is critical to avoid blocking code, especially on time-critical systems like the power board since you want the MCU to be as responsive as possible to any illegal or hazardous changes, like water in the hull, low battery voltage, very high hull temperature, ... Check out this page on blocking code, and ensure to make your overall code as non-blocking as possible.

Declaring the ROS Node

Create a ROS node:

ros::NodeHandle nh;

Declaring Subscribers

Set up subscribers with:

ros::Subscriber<auv_msgs::ThrusterMicroseconds> sub(
    "/propulsion/microseconds",
    &commandCb
);
  • First parameter: Message type.
  • Second parameter: Topic name (use descriptive names).
  • Third parameter: Callback function to process data changes.

Declaring Publishers

Set up publishers with:

ros::Publisher batt1_voltage(
    "/power/batteries/voltage/1",
    &batt1_voltage_msg
);
  • First parameter: Topic name.
  • Second parameter: Pointer to the message.

To publish data:

batt1_voltage_msg.data = Bvoltages[0];
batt1_voltage.publish(&batt1_voltage_msg);

Setting Up and Looping

Setup Function

Initialize your system and set up ROS components in setup:

void setup() {
    nh.initNode();
    nh.subscribe(sub);
    nh.advertise(batt1_voltage);
    // Other setup code
}

Loop Function

In the loop function, perform logic, publish data, and ensure ROS processes are running:

void loop() {
    // Logic and data updates
    batt1_voltage_msg.data = Bvoltages[0];
    batt1_voltage.publish(&batt1_voltage_msg);

    nh.spinOnce();
    delay(10);
}

Reference Code

Here is a complete example for reference:

#include <Arduino.h> // Required (might be done by default based on build system)
#include <ros.h> // Import ROS library
#include <auv_msgs/ThrusterMicroseconds.h> // Import custom messages
#include <std_msgs/Float32.h> // Import standard messages

// Pin and variable definitions
#define BACK_L_PIN 2 // some code
#define LED_PIN 13 // some code

std_msgs::Float32 batt1_voltage_msg; // Declare ROS messages

uint16_t microseconds[] = {1500}; // some code

// Callback function
void commandCb(const auv_msgs::ThrusterMicroseconds &tc) { // Initialize callback functions for every subscriber
    memcpy(microseconds, tc.microseconds, sizeof(uint16_t)); // this copies the subscriber array to a local array
}

// ROS node and subscribers/publishers
ros::NodeHandle nh; // Declare ROS node
ros::Subscriber<auv_msgs::ThrusterMicroseconds> sub("/propulsion/microseconds", &commandCb); // Decalre subscribers
ros::Publisher batt1_voltage("/power/batteries/voltage/1", &batt1_voltage_msg); // Declare publishers

void setup() {
    // some setup code
    pinMode(BACK_L_PIN, OUTPUT); // some code - setup logic

    nh.initNode(); // Init ROS node
    nh.subscribe(sub); // Init subscribers
    nh.advertise(batt1_voltage); // Init publishers

    // more setup code
}

void loop() {
    // some loop code

    batt1_voltage_msg.data = analogRead(A0) * (5.0 / 1023.0); // Assign obtained data to message
    batt1_voltage.publish(&batt1_voltage_msg); // Publish message
    nh.spinOnce(); // Spin the executor - will do subscriber callback
    delay(10); // delay

    // more loop code
}

By following this tutorial, you should have a good understanding of how to use ROSSerial in your projects. Always document your work and ensure clear communication with other teams to maintain a cohesive system.

Publishing in terminal

rostopic pub /propulsion/microseconds auv_msgs/ThrusterMicroseconds "{microseconds: [1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500]}"
rostopic echo /propulsion/microseconds | awk '{print strftime("%Y-%m-%d %H:%M:%S"), $0}' | tee output.txt
rostopic echo -p /propulsion/microseconds | tee output.csv
Clone this wiki locally