MAUVE ROS
Publisher and Subscriber components
MAUVE ROS provides a component version of the publisher and subscriber, to be used for the cases where:
- the data to publish/subscribe is not written/read from a component
- you need to manage the rate at which data are published/subscribed to ROS
PublisherComponent
The PublisherComponent has the same properties than the PublisherResource (i.e. topic and conversion).
It also has a ReadPort on which the component reads data and publish it to ROS.
The component FSM has a period property to manage the publishing rate.
The following code snippet shows how to use the PublisherComponent:
struct MyArchitecture : public mauve::runtime::Architecture {
(...)
mauve::ros::PublisherComponent<std::string, std_msgs::String> & string_publisher =
mk_component<mauve::ros::PublisherComponent<std::string, std_msgs::String>>("string_publisher");
mauve::runtime::SharedData<std::string> & text =
mk_resource<mauve::runtime::SharedData<std::string>>("text", "");
(...)
bool configure_hook() {
(...)
string_publisher.shell().read_port.connect(text.interface().read);
(...)
string_publisher.shell().topic = "my_text";
string_publisher.shell().conversion.set_value(mauve::ros::conversions::convert<std::string,std_msgs::String>);
string_publisher.fsm().period = mauve::runtime::ms_to_ns(100);
(...)
return mauve::runtime::Architecture::configure_hook();
}
};
SubscriberComponent
The SubscriberComponent behaves similarly, with a WritePort to write data received trom ROS.
The following code snippet shows how to use the SubscriberComponent:
struct MyArchitecture : public mauve::runtime::Architecture {
(...)
mauve::ros::SubscriberComponent<std::string, std_msgs::String> & string_subscriber =
mk_component<mauve::ros::SubscriberComponent<std::string, std_msgs::String>>("string_subscriber");
mauve::runtime::SharedData<std::string> & text =
mk_resource<mauve::runtime::SharedData<std::string>>("text", "");
(...)
bool configure_hook() {
(...)
string_subscriber.shell().write_port.connect(text.interface().write);
(...)
string_subscriber.shell().topic = "my_text";
string_subscriber.shell().conversion.set_value(mauve::ros::conversions::convert<std_msgs::String,std::string>);
string_subscriber.fsm().period = mauve::runtime::ms_to_ns(100);
(...)
return mauve::runtime::Architecture::configure_hook();
}
};