ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
well, if you want to publish the joint state by yourself, try the following code:
#include <string>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <tf/transform_broadcaster.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "myRobot_move_joint");
ros::NodeHandle n;
ros::Publisher joint_pub = n.advertise<sensor_msgs::JointState>("joint_states", 1);
tf::TransformBroadcaster broadcaster;
ros::Rate loop_rate(30);
const double degree = M_PI/180;
double rot4 = 90;
geometry_msgs::TransformStamped odom_trans;
sensor_msgs::JointState joint_state;
odom_trans.header.frame_id = "odom";
odom_trans.child_frame_id = "base_link";
joint_state.name.resize(7);
joint_state.position.resize(7);
joint_state.name[0] ="base_to_left_link1";
joint_state.name[1] ="left_link1_to_left_link2";
joint_state.name[2] ="left_link2_to_left_link3";
joint_state.name[3] ="left_link3_to_left_link4";
joint_state.name[4] ="left_link4_to_left_link5";
joint_state.name[5] ="left_link5_to_left_link6";
joint_state.name[6] ="left_link6_to_left_link7";
while (ros::ok()) {
//update joint_state
joint_state.header.stamp = ros::Time::now();
joint_state.position[0] = 0;
joint_state.position[1] = 0;
joint_state.position[2] = 0;
joint_state.position[3] = rot4*degree;
joint_state.position[4] = 0;
joint_state.position[5] = 0;
joint_state.position[6] = 0;
// update transform
// (moving in a circle with radius=2)
odom_trans.header.stamp = ros::Time::now();
odom_trans.transform.translation.x = 0;
odom_trans.transform.translation.y = 0;
odom_trans.transform.translation.z = 0;
odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(0);
//send the joint state and transform
joint_pub.publish(joint_state);
broadcaster.sendTransform(odom_trans);
rot4 += 1;
if (rot4 > 90) rot4 = 0;
loop_rate.sleep();
}
return 0;
}
this works for my 7DOF robot arm. just change the joint names to your own.