MAUVE ROS

Subscribe data from ROS

The basic element to subscribe some data from ROS is the MAUVE SubscriberResource.

The SubscriberResource has a Shell with:

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

The SubscriberResource has an Interface with:

  • a read service so that a component can read the received data along with a status
  • a read_value service so that a component can read the received data (independently of the status)
  • a read_status service so that a component can read the received data status

The SubscriberResource 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 subscribes a string from ROS through a SubscriberResource.

First, include the mauve_ros headers:

#include <mauve/ros.hpp>

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

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

In the architecture configure_hook, connect the ReadPort of the component to the resource, and configure the subscriber properties:

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

The conversion function used by the subscriber 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 subscriber property, of by defining a lambda function. For instance, the following code defines a custom function:

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

This conversion function will not accept empty strings.

results matching ""

    No results matching ""