MAUVE ROS

Publish data to ROS

The basic element to publish some data to ROS is the MAUVE PublisherResource.

The PublisherResource has a Shell with:

  • a topic property to define the ROS topic to publish to
  • a conversion property to define the conversion function between your internal type and a ROS message

The PublisherResource has an Interface with:

  • a write service so that a component can write to publish a message

The PublisherResource is templated by the internal MAUVE type and the ROS message type.

Code samples

Here is a simple example of an architecture with a component that publishes a string to ROS through a PublisherResource.

First, include the mauve_ros headers:

#include <mauve/ros.hpp>

In your architecture, add a PublisherResource that convert a string into a ROS String:

mauve::ros::PublisherResource<std::string, std_msgs::String> & string_publisher =
  mk_resource<mauve::ros::PublisherResource<std::string, std_msgs::String>>("string_publisher");

In the architecture configure_hook, connect the WritePort of the component to the resource, and configure the publisher properties:

bool configure_hook() {
  my_component.shell().write_port.connect(string_publisher.interface().write);
  string_publisher.shell().topic = "my_str";
  string_publisher.shell().conversion.set_value(mauve::ros::conversions::convert<std::string,std_msgs::String>);
}

The conversion function used by the publisher is one of the converters provided by MAUVE. The complete list of MAUVE/ROS conversion functions is lister there.

Instead of using the provided conversions, you can specify your own conversion by passing a function pointer to the publisher property, of by defining a lambda function. For instance, the following code defines a custom function:

string_publisher.shell().conversion.set_value([](const std::string& data, std_msgs::String& msg) -> bool {
  if (data.empty()) return false;
  else {
    msg.data = data;
    return true;
  }
});

This conversion function will not publish empty strings.

results matching ""

    No results matching ""