JointStatePublisher.cpp
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2010 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * JointStatePublisher.cpp
20  *
21  * Created on: 06.12.2010
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 
26 
27 namespace katana
28 {
29 
31  katana(katana)
32 {
33  ros::NodeHandle nh;
34  pub = nh.advertise<sensor_msgs::JointState> ("joint_states", 1000);
35 }
36 
38 {
39 }
40 
42 {
43  /* ************** Publish joint angles ************** */
44  sensor_msgs::JointStatePtr msg = boost::make_shared<sensor_msgs::JointState>();
45  std::vector<std::string> joint_names = katana->getJointNames();
46  std::vector<double> angles = katana->getMotorAngles();
47  std::vector<double> vels = katana->getMotorVelocities();
48 
49  for (size_t i = 0; i < NUM_JOINTS; i++)
50  {
51  msg->name.push_back(joint_names[i]);
52  msg->position.push_back(angles[i]);
53  msg->velocity.push_back(vels[i]);
54  }
55 
56  msg->name.push_back(katana->getGripperJointNames()[0]);
57  msg->position.push_back(angles[5]);
58  msg->velocity.push_back(vels[5]);
59 
60  msg->name.push_back(katana->getGripperJointNames()[1]);
61  msg->position.push_back(angles[5]); // both right and left finger are controlled by motor 6
62  msg->velocity.push_back(vels[5]);
63 
64  msg->header.stamp = ros::Time::now();
65  pub.publish(msg); // NOTE: msg must not be changed after publishing; use reset() if necessary (http://www.ros.org/wiki/roscpp/Internals)
66 }
67 
68 }
void publish(const boost::shared_ptr< M > &message) const
JointStatePublisher(boost::shared_ptr< AbstractKatana >)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)


katana
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:58