Subscribe to custom message

Hello Mike,

It is possible to create custom message to exchange data between CORE2 and other ROS nodes.

I will explain it based on package created for this post, we will name this package custom_pkg.

First part is to build node for SBC side:

Begin with creating the package:

cd ~ros_workspace/src
catkin_create_pkg custom_pkg roscpp std_msgs

Then open CMakeLists.txt and edit it as below:

cmake_minimum_required(VERSION 2.8.3)
project(custom_pkg)

add_compile_options(-std=c++11)

find_package(catkin REQUIRED COMPONENTS
  message_generation
  roscpp
  std_msgs
)

add_message_files(
  FILES
  VehicleControl.msg
)

generate_messages(
  DEPENDENCIES
  std_msgs
)

catkin_package(
 CATKIN_DEPENDS
)

include_directories(
include
  ${catkin_INCLUDE_DIRS}
)

add_executable(${PROJECT_NAME}_node src/custom_pkg_node.cpp)
add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

target_link_libraries(${PROJECT_NAME}_node
  ${catkin_LIBRARIES}
)

In package directory create msg folder and message file. Name it VehicleControl.msg and paste contents:

Header header
std_msgs/String Direction
std_msgs/UInt32 Distance
std_msgs/String Unit    

You can use message as any other ROS message:

#include "ros/ros.h"
#include <custom_pkg/VehicleControl.h>

custom_pkg::VehicleControl vehicleControl;

int main(int argc, char **argv)
{
    ros::init(argc, argv, "custom_node");
    ros::NodeHandle n;

    ros::Publisher vehicle_pub = n.advertise<custom_pkg::VehicleControl>("vehicle_control", 1);
    ros::Rate loop_rate(10);

    vehicleControl.header.frame_id = "base_link";
    vehicleControl.Direction.data = "forward";
    vehicleControl.Distance.data = 1;
    vehicleControl.Unit.data = "m";
    while (ros::ok())
    {
        vehicle_pub.publish(vehicleControl);
        ros::spinOnce();
        loop_rate.sleep();
    }
    return 0;
}

Please note that we created only VehicleControl.msg file, while we are including custom_pkg/VehicleControl.h. Corresponding header file for message will be created during catkin_make.

Build it and you will get a ROS node that publishes your custom message.

Second part will be building message for CORE2 side:

For communication between CORE2 and other ROS components we are using rosserial. Header files for rosserial are suited for controllers like STM32 boards or Arduino.

We can generate headers for rosserial, it must be done on SBC side, make sure that message is defined properly:

rosmsg show custom_pkg/VehicleControl

You should get output like below:

std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
std_msgs/String Direction
  string data
std_msgs/UInt32 Distance
  uint32 data
std_msgs/String Unit
  string data

We can generate rosserial headers:

cd ~/ros_worskpace
mkdir rosserial_lib
rosrun rosserial_client make_libraries rosserial_lib/

This will generate headers for all messages in system. Our file will be in ~/ros_worskpace/rosserial_lib/ros_lib/custom_pkg/. Copy file VehicleControl.h from that directory to cloud IDE.

VeicleControl message may be used as any other ROS message:

#include "hFramework.h"
#include "hCloudClient.h"
#include "ros.h"
#include "VehicleControl.h"

using namespace hFramework;

ros::NodeHandle nh;

void controlCallback(const custom_pkg::VehicleControl &control)
{
    int new_speed = control.Distance.data;
    if(new_speed == 1){
        LED2.toggle();
    }
}

void hMain()
{
	RPi.init(500000);
	platform.begin(&RPi);
	nh.getHardware()->initWithDevice(&platform.LocalSerial);
	nh.initNode();
	ros::Subscriber<custom_pkg::VehicleControl> *control_sub = new ros::Subscriber<custom_pkg::VehicleControl>("/vehicle_control", &controlCallback);
	nh.subscribe(*control_sub);
	while (true)
	{
	    LED1.toggle();
		nh.spinOnce();
		sys.delay(10);
	}
}

In separate terminal windows start:

  • roscore
  • /opt/husarion/tools/rpi-linux/ros-core2-client /dev/ttyCORE2
  • rosrun custom_pkg custom_pkg_node

LED2 on ROSbot back panel will blink with every message received.

Regards,
Ɓukasz