Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #include "katana/JointStatePublisher.h"
00026
00027 namespace katana
00028 {
00029
00030 JointStatePublisher::JointStatePublisher(boost::shared_ptr<AbstractKatana> katana) :
00031 katana(katana)
00032 {
00033 ros::NodeHandle nh;
00034 pub = nh.advertise<sensor_msgs::JointState> ("joint_states", 1000);
00035 }
00036
00037 JointStatePublisher::~JointStatePublisher()
00038 {
00039 }
00040
00041 void JointStatePublisher::update()
00042 {
00043
00044 sensor_msgs::JointStatePtr msg = boost::make_shared<sensor_msgs::JointState>();
00045 std::vector<std::string> joint_names = katana->getJointNames();
00046 std::vector<double> angles = katana->getMotorAngles();
00047 std::vector<double> vels = katana->getMotorVelocities();
00048
00049 for (size_t i = 0; i < NUM_JOINTS; i++)
00050 {
00051 msg->name.push_back(joint_names[i]);
00052 msg->position.push_back(angles[i]);
00053 msg->velocity.push_back(vels[i]);
00054 }
00055
00056 msg->name.push_back(katana->getGripperJointNames()[0]);
00057 msg->position.push_back(angles[5]);
00058 msg->velocity.push_back(vels[5]);
00059
00060 msg->name.push_back(katana->getGripperJointNames()[1]);
00061 msg->position.push_back(angles[5]);
00062 msg->velocity.push_back(vels[5]);
00063
00064 msg->header.stamp = ros::Time::now();
00065 pub.publish(msg);
00066 }
00067
00068 }