Message Type mismatch in Baxter while using Gazebo Simulator
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. Before writing the code, I looked in the list of rostopics, by executing rostopic list
command. Later on, I found out that /robot/limb/right/joint_command
topic is used for controlling the joints. I looked in this ros message for more info. Below is the command run at terminal-
[baxter - http://localhost:11311] ravi@dell:~/ros_ws$ rostopic info /robot/limb/right/joint_command
Type: sensor_msgs/JointState
Publishers: None
Subscribers:
* /gazebo (http://localhost:45341/)
Based on the above output, I write following code-
ros::init(argc, argv, "move_joints");
ros::NodeHandle node;
ros::Publisher joint_pub = node.advertise<sensor_msgs::JointState>("/robot/limb/right/joint_command",10);
sensor_msgs::JointState joint_state;
joint_state.name.push_back("right_e0");
joint_state.name.push_back("right_e1");
//The remaining lines are not being shown here, to shorten the code
joint_state.position.push_back(0.0);
joint_state.position.push_back(0.0);
//The remaining lines are not being shown here, to shorten the code
I complied the code using catkin_make
and it compiled successfully without any error. But while running the code, it throws the error. Please see the below output from terminal-
[baxter - http://localhost:11311] ravi@dell:~/ros_ws$ rosrun tools move_joints
[ERROR] [1448935306.651614576]: Client [/gazebo] wants topic /robot/limb/right/joint_command to have datatype/md5sum [baxter_core_msgs/JointCommand/19bfec8434dd568ab3c633d187c36f2e], but our version has [sensor_msgs/JointState/3066dcd76a6cfaef579bd0f34173e9fd]. Dropping connection.
This gives me a hint that the message type mismatch is occurred. Somebody help me to overcome with this issue.
Are you sure that your command at the top is correct? For me
rostopic info /robot/limb/right/joint_command
returnsType: baxter_core_msgs/JointCommand
(consistent with your error). What branch/tag is your simulator on? On v1.1.1 tag the "baxter_gazebo_ros_control_plugin.cpp" file...... indicates that the subscriber on the
/robot/limb/right/joint_command
topic should be of typebaxter_core_msgs::JointCommand
.