ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

This is the main(..) from the code you link in your question:

int main(int argc, char **argv)
{
    /*
    * Main loop of the hardware interface.
    */
    ros::init(argc, argv, "hw_interface");
    MyRobot robot;
    controller_manager::ControllerManager cm(&robot);
    ros::Time time_now;
    ros::Duration period_now;
    ros::Rate sleep_rate(10);


    while (true)
    {
        time_now = robot.get_time();
        period_now = robot.get_period(); 
        robot.read(period_now);
        cm.update(time_now, period_now);
        robot.write();
        sleep_rate.sleep();
    }
}

There is one thing suspiciously missing here, and that would be somewhere for ROS to actually process events.

Even a hardware_interface needs some time to process incoming and outgoing events, but you don't give it any.

You'll either want to call ros::spinOnce() somewhere in your while loop, or instantiate a ros::AsyncSpinner and start it. The latter would actually be recommended. Something like this should do the trick:

ros::AsyncSpinner spinner(2);
spinner.start();

A single thread is not enough, as there is a high potential for deadlocks.

Note that this also done in the two examples that you link: PickNikRobotics/ros_control_boilerplate (here) and eborghi10/my_ROS_mobile_robot (here).

This is the main(..) from the code you link in your question:

int main(int argc, char **argv)
{
    /*
    * Main loop of the hardware interface.
    */
    ros::init(argc, argv, "hw_interface");
    MyRobot robot;
    controller_manager::ControllerManager cm(&robot);
    ros::Time time_now;
    ros::Duration period_now;
    ros::Rate sleep_rate(10);


    while (true)
    {
        time_now = robot.get_time();
        period_now = robot.get_period(); 
        robot.read(period_now);
        cm.update(time_now, period_now);
        robot.write();
        sleep_rate.sleep();
    }
}

There is one thing suspiciously missing here, and that would be somewhere for ROS to actually process events.events. The fact that the controller_manager services do not produce any output is indicative of this.

Even a hardware_interface needs some time to process incoming and outgoing events, but you don't give it any.

You'll either want to call ros::spinOnce() somewhere in your while loop, or instantiate a ros::AsyncSpinner and start it. The latter would actually be recommended. Something like this should do the trick:

ros::AsyncSpinner spinner(2);
spinner.start();

A single thread is not enough, as there is a high potential for deadlocks.

Note that this also done in the two examples that you link: PickNikRobotics/ros_control_boilerplate (here) and eborghi10/my_ROS_mobile_robot (here).

This is the main(..) from the code you link in your question:

int main(int argc, char **argv)
{
    /*
    * Main loop of the hardware interface.
    */
    ros::init(argc, argv, "hw_interface");
    MyRobot robot;
    controller_manager::ControllerManager cm(&robot);
    ros::Time time_now;
    ros::Duration period_now;
    ros::Rate sleep_rate(10);


    while (true)
    {
        time_now = robot.get_time();
        period_now = robot.get_period(); 
        robot.read(period_now);
        cm.update(time_now, period_now);
        robot.write();
        sleep_rate.sleep();
    }
}

There is one thing suspiciously missing here, and that would be somewhere for ROS to actually process events. The fact that the controller_manager services do not produce any output is indicative of this.

Even a hardware_interface needs some time to process incoming and outgoing events, but you don't give it any.

You'll either want to call ros::spinOnce() somewhere in your while loop, or instantiate a ros::AsyncSpinner and start it. The latter would actually be recommended. Something like this should do the trick:

ros::AsyncSpinner spinner(2);
spinner.start();

A single thread is not enough, as there is a high potential for deadlocks.

Note that this also done in the two examples that you link: PickNikRobotics/ros_control_boilerplate (here) and eborghi10/my_ROS_mobile_robot (here).


Edit: just noticed you have this:

while (true)
{
  [..]
}

This is not a good idea in a ROS node -- which a hardware_interface essentially is.

You'll want to check for ros::ok() instead.