$search
00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2010 University of Osnabrück 00004 * 00005 * This program is free software; you can redistribute it and/or 00006 * modify it under the terms of the GNU General Public License 00007 * as published by the Free Software Foundation; either version 2 00008 * of the License, or (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00018 * 00019 * JointStatePublisher.cpp 00020 * 00021 * Created on: 06.12.2010 00022 * Author: Martin Günther <mguenthe@uos.de> 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 /* ************** Publish joint angles ************** */ 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]); // both right and left finger are controlled by motor 6 00062 msg->velocity.push_back(vels[5]); 00063 00064 msg->header.stamp = ros::Time::now(); 00065 pub.publish(msg); // NOTE: msg must not be changed after publishing; use reset() if necessary (http://www.ros.org/wiki/roscpp/Internals) 00066 } 00067 00068 }