ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
There are several approaches to using a player driver in ROS:
Wrapping the player library in a ROS node (like erratic_player does).
Converting the driver to ROS manually.
The first probably gets the job done quicker, but is harder to maintain. With a little practice, the second is relatively straightforward. I've done quite a few. If you have follow-up questions, feel free to ask.
When converting a player driver to a ROS node, the class inherited from the player Driver class is no longer needed and just adds unnecessary complexity.
Make a simple C++ main program, something like this:
int main(int argc, char** argv)
{
ros::init(argc, argv, NODE);
ros::NodeHandle node;
// topics to read and write
brake_cmd = node.subscribe(NODE "/cmd", 10, ProcessCommand,
ros::TransportHints().tcpNoDelay(true));
brake_state = node.advertise<art_brake::State>(NODE "/state", 10);
if (GetParameters() != 0) // from the player constructor
return 1;
ros::Rate cycle(HERTZ_BRAKE); // set driver cycle rate
if (Setup() != 0) // from the player Setup()
return 2;
// Main loop; grab messages off our queue and republish them via ROS
while(ros::ok())
{
... // activities from player Main()
cycle.sleep(); // sleep until next cycle
}
Shutdown();
return 0;
}
2 | make example a little more generic |
There are several approaches to using a player driver in ROS:
Wrapping the player library in a ROS node (like erratic_player does).
Converting the driver to ROS manually.
The first probably gets the job done quicker, but is harder to maintain. With a little practice, the second is relatively straightforward. I've done quite a few. If you have follow-up questions, feel free to ask.
When converting a player driver to a ROS node, the class inherited from the player Driver class is no longer needed and just adds unnecessary complexity.
Make a simple C++ main program, something like this:
int main(int argc, char** argv)
{
ros::init(argc, argv, NODE);
ros::NodeHandle node;
// topics to read and write
brake_cmd = node.subscribe(NODE "/cmd", node.subscribe("cmd", 10, ProcessCommand,
ros::TransportHints().tcpNoDelay(true));
brake_state = node.advertise<art_brake::State>(NODE "/state", node.advertise<art_brake::State>("state", 10);
if (GetParameters() != 0) // from the player constructor
return 1;
ros::Rate cycle(HERTZ_BRAKE); cycle(20.0); // set driver cycle rate
if (Setup() != 0) // from the player Setup()
return 2;
// Main loop; grab messages off our queue and republish them via ROS
while(ros::ok())
{
... // activities from player Main()
cycle.sleep(); // sleep until next cycle
}
Shutdown();
return 0;
}