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

Why publish the same command multiple times to reach a position?

asked 2015-12-01 06:25:28 -0600

ravijoshi gravatar image

Hi,

I am learning Baxter Robot using ROS in C++ language. For getting used to with ROS and Baxter, I am writing a C++ program to control Joint position. A joint position is defined and it is published to /robot/limb/right/joint_command topic. Below is the snippet of the code-

int main(int argc, char **argv)
{
    //Initializen the ros
    ros::init(argc, argv, "move_joints");

    //Declare the node handle
    ros::NodeHandle node;

    //Decleare a joint state publisher
    ros::Publisher joint_pub = node.advertise<baxter_core_msgs::JointCommand>("/robot/limb/right/joint_command",10);

    //Define the joint state
    baxter_core_msgs::JointCommand joint_cmd;

    //Set the mode
    joint_cmd.mode = baxter_core_msgs::JointCommand::POSITION_MODE;

    //names is a std::vector<std::string>
    joint_cmd.names.push_back("right_e0");//Joint 1
    joint_cmd.names.push_back("right_e1");//Joint 2
    joint_cmd.names.push_back("right_s0");//Joint 3
    joint_cmd.names.push_back("right_s1");//Joint 4
    joint_cmd.names.push_back("right_w0");//Joint 5
    joint_cmd.names.push_back("right_w1");//Joint 6
    joint_cmd.names.push_back("right_w2");//Joint 7

    //position is a std::vector<double>
    joint_cmd.command.push_back(degree_to_radian(30.0));//Joint 1
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 2
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 3
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 4
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 5
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 6
    joint_cmd.command.push_back(degree_to_radian(0.0));//Joint 7

    //command the robot to move
    joint_pub.publish(joint_cmd);
    ros::spinOnce();

    cout << joint_cmd << endl;

    return 0;
}

The above code DOES NOT work. But when I put the publish method, inside a while (ros::ok()) loop in the following way, it works fine-

ros::Rate loop_rate(10);

while (ros::ok())
{
    //command the robot to move
    joint_pub.publish(joint_cmd);
    ros::spinOnce();
    loop_rate.sleep();

    cout << joint_cmd << endl;
}

I was expecting to move the right arm and reach to the desired position in a single command. But it did not move in a single command. My question is that why we need to send the joint command multiple times? What is the reason behind this? More preciously, how many times a command must be published so that it executes?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2015-12-01 07:03:27 -0600

This behavior is explained clearly on the Arm Control Modes page of the Baxter SDK Wiki. Quoting from the Joint Control Fundamentals section:

A control rate timeout is also enforced at this motor controller layer. This states that if a new 'JointCommand' message is not received within the specified timeout (0.2 seconds, or 5Hz), the robot will 'Timeout'. When the robot 'Times out', the current control mode is exited, reverting back to position control mode where the robot will command (hold) it's current joint angles. The reason for this is safety. For example, if controlling in velocity control mode where you are commanding 1.0 Rad/s to joint S0, and you lose network connectivity (someone kicks your router), the robot could result in dangerous motions. By 'timing out', the robot will be safer, reacting to network timeouts, or incorrect control behavior.

Also note that if you want to disable this safety feature, you may do so (be careful!). This is explained on the previously-linked page.

edit flag offensive delete link more

Comments

2

And just to clarify this a bit: publishing once and calling spinOnce()once will also most likely not work, even without the safety feature of Baxter. ROS probably won't have enough time to properly transmit your message in that short time.

gvdhoorn gravatar image gvdhoorn  ( 2015-12-01 07:46:32 -0600 )edit

Okay. But how many times the command needs to be published? Currently it is written inside while (ros::ok()) loop. What if I want to oscillate between two two set of joint positions? How to handle these situations?

ravijoshi gravatar image ravijoshi  ( 2015-12-10 03:44:43 -0600 )edit

The number of times you need to publish the command depends entirely on how far the arm has to move (i.e. how long it will take to get there). Your best bet is writing a controller that compares the current joint values with the desired values and publishes until the error is within a tolerance.

jarvisschultz gravatar image jarvisschultz  ( 2015-12-10 06:31:20 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2015-12-01 06:25:28 -0600

Seen: 1,264 times

Last updated: Dec 01 '15