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

Joint Control in Baxter using ROS in C++

asked 2015-11-30 05:31:14 -0500

ravijoshi gravatar image

Hi,

I am a beginner in ROS. I am trying to control Baxter Robot using ROS in C++ language. I want to move Baxter in Joint Level Control by providing each joint angels. Since, this is my learning phase, so I am avoiding python API for now. However I have already tried python API from the Baxter official website.

Well, I tried printing the current joint angles by subscribing to /robot/joint_states topic in the following way node.subscribe("/robot/joint_states",100,printJointStates);. It works perfectly. Now, I wanted to move the joints. So I tried to publish the data into /robot/limb/right/joint_command topic. Below is the complete code-

#include <ros/ros.h>
#include <sensor_msgs/JointState.h>

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<sensor_msgs::JointState>("/robot/limb/right/joint_command",10);

    //Define the joint state
    sensor_msgs::JointState joint_state;

    joint_state.name[0] = "right_e0";
    joint_state.name[1] = "right_e1";
    joint_state.name[2] = "right_s0";
    joint_state.name[3] = "right_s1";
    joint_state.name[4] = "right_w0";
    joint_state.name[5] = "right_w1";
    joint_state.name[6] = "right_w2";

    joint_state.position[0] = 0.0;
    joint_state.position[1] = 0.0;
    joint_state.position[2] = 0.0;
    joint_state.position[3] = 0.0;
    joint_state.position[4] = 0.0;
    joint_state.position[5] = 0.0;
    joint_state.position[6] = 0.0;

    //command the robot to move
    joint_pub.publish(joint_state);

    ros::spinOnce();

    return 0;
}

The code compiles without any error but shows following error in the run time- segmentation fault (core dumped)

I suspect that the JointState is not properly defined. Please note that I am using ROS Indigo in Ubuntu 14.04 LTS 64 Bit OS. I am using Gazebo simulator to test this code.

I am unable to proceed further. Please provide your suggestions.

edit retag flag offensive close merge delete

Comments

Hi, I am wondering if you could send me your code for the subscriber. I am also a beginner and trying to get a subscriber and publisher thing going as well.

Thanks.

justinkgoh gravatar image justinkgoh  ( 2016-07-05 12:36:03 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2015-11-30 08:26:32 -0500

imcmahon gravatar image

Messages in ROS are compiled into compatible C++ structures. Here joint_state.name is a std::vector<std::string> and joint_state.position is a std::vector<double>. When adding elements to these structures, you need to use the standard methods of adding elements to a C++ vector, such as
joint_state.position.push_back(0.0);

or by first resizing the joint_state.position vector:
joint_state.position.resize(7); // and then index as you do above
joint_state.position[0] = 0.0;

I happen to have a Github Gist that commands Baxter's arms with C++, quite similar to your code (sans the coredump :)

https://gist.github.com/rethink-imcma...

One potential "gotcha" here is that you will need to command Baxter's arms at a rate greater than 5Hz. Otherwise, they will revert back into position mode and hold their place. This is a safety feature.

And for a few helpful links -

edit flag offensive delete link more

Comments

Thank you very much. Happy to see a detailed answer. I appreciate it!!!

ravijoshi gravatar image ravijoshi  ( 2015-11-30 09:08:41 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-11-30 05:31:14 -0500

Seen: 3,621 times

Last updated: Nov 30 '15