34 pub = nh.
advertise<sensor_msgs::JointState> (
"joint_states", 1000);
44 sensor_msgs::JointStatePtr msg = boost::make_shared<sensor_msgs::JointState>();
45 std::vector<std::string> joint_names =
katana->getJointNames();
47 std::vector<double> vels =
katana->getMotorVelocities();
51 msg->name.push_back(joint_names[i]);
52 msg->position.push_back(angles[i]);
53 msg->velocity.push_back(vels[i]);
56 msg->name.push_back(
katana->getGripperJointNames()[0]);
57 msg->position.push_back(angles[5]);
58 msg->velocity.push_back(vels[5]);
60 msg->name.push_back(
katana->getGripperJointNames()[1]);
61 msg->position.push_back(angles[5]);
62 msg->velocity.push_back(vels[5]);
void publish(const boost::shared_ptr< M > &message) const
virtual ~JointStatePublisher()
JointStatePublisher(boost::shared_ptr< AbstractKatana >)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)