AbstractKatana.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  * AbstractKatana.cpp
20  *
21  * Created on: 20.12.2010
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 
25 #include <katana/AbstractKatana.h>
26 
27 namespace katana
28 {
29 
31 {
32  // names and types for the 5 "real" joints
33  joint_names_.resize(NUM_JOINTS);
34  joint_types_.resize(NUM_JOINTS);
35 
36  // names and types for the 2 "finger" joints
37 
40 
41  // angles and velocities and limits: the 5 "real" joints + gripper
42  motor_angles_.resize(NUM_MOTORS);
44  motor_limits_.resize(NUM_MOTORS + 1);
45 
46  /* ********* get parameters ********* */
47  // ros::NodeHandle pn("~");
49 
50  std::string robot_desc_string;
51 
52  if (!n.getParam("robot_description", robot_desc_string))
53  {
54  ROS_FATAL("Couldn't get a robot_description from the param server");
55  return;
56  }
57 
58  urdf::Model model;
59  model.initString(robot_desc_string);
60 
61  XmlRpc::XmlRpcValue joint_names;
62 
63  // Gets all of the joints
64  if (!n.getParam("katana_joints", joint_names))
65  {
66  ROS_ERROR("No joints given. (namespace: %s)", n.getNamespace().c_str());
67  }
68  if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
69  {
70  ROS_ERROR("Malformed joint specification. (namespace: %s)", n.getNamespace().c_str());
71  }
72  if (joint_names.size() != (size_t)NUM_JOINTS)
73  {
74  ROS_ERROR("Wrong number of joints! was: %d, expected: %zu", joint_names.size(), NUM_JOINTS);
75  }
76  for (size_t i = 0; i < NUM_JOINTS; ++i)
77  {
78  XmlRpc::XmlRpcValue &name_value = joint_names[i];
79  if (name_value.getType() != XmlRpc::XmlRpcValue::TypeString)
80  {
81  ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)",
82  n.getNamespace().c_str());
83  }
84 
85  joint_names_[i] = (std::string)name_value;
86  joint_types_[i] = urdf::Joint::REVOLUTE; // all of our joints are of type revolute
87 
88  motor_limits_[i].joint_name = (std::string)name_value;
89  motor_limits_[i].min_position = model.getJoint(joint_names_[i])->limits->lower;
90  motor_limits_[i].max_position = model.getJoint(joint_names_[i])->limits->upper;
91 
92  //ROS_INFO("Setting MotorLimit for %s to min: %f - max: %f", motor_limits_[i].joint_name.c_str(), motor_limits_[i].min_position, motor_limits_[i].max_position);
93 
94  }
95 
96  XmlRpc::XmlRpcValue gripper_joint_names;
97 
98  // Gets all of the joints
99  if (!n.getParam("katana_gripper_joints", gripper_joint_names))
100  {
101  ROS_ERROR("No gripper_joints given. (namespace: %s)", n.getNamespace().c_str());
102  }
103  if (gripper_joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
104  {
105  ROS_ERROR("Malformed gripper_joint specification. (namespace: %s)", n.getNamespace().c_str());
106  }
107  if ((size_t)gripper_joint_names.size() != NUM_GRIPPER_JOINTS)
108  {
109  ROS_ERROR("Wrong number of gripper_joints! was: %d, expected: %zu", gripper_joint_names.size(), NUM_GRIPPER_JOINTS);
110  }
111  for (size_t i = 0; i < NUM_GRIPPER_JOINTS; ++i)
112  {
113  XmlRpc::XmlRpcValue &name_value = gripper_joint_names[i];
114  if (name_value.getType() != XmlRpc::XmlRpcValue::TypeString)
115  {
116  ROS_ERROR("Array of gripper joint names should contain all strings. (namespace: %s)",
117  n.getNamespace().c_str());
118  }
119 
120  gripper_joint_names_[i] = (std::string)name_value;
121  gripper_joint_types_[i] = urdf::Joint::REVOLUTE; // all of our joints are of type revolute
122 
123  motor_limits_[NUM_JOINTS + i].joint_name = (std::string)name_value;
124  motor_limits_[NUM_JOINTS + i].min_position = model.getJoint(gripper_joint_names_[i])->limits->lower;
125  motor_limits_[NUM_JOINTS + i].max_position = model.getJoint(gripper_joint_names_[i])->limits->upper;
126 
127  // ROS_INFO("Setting MotorLimit for %s to min: %f - max: %f", motor_limits_[NUM_JOINTS + i].joint_name.c_str(), motor_limits_[NUM_JOINTS + i].min_position, motor_limits_[NUM_JOINTS + i].max_position);
128  }
129 }
130 
132 {
133 }
134 
136 {
137  // do nothing (can be overridden)
138 }
139 
141 {
142  // do nothing (can be overridden)
143 }
144 
145 /* ******************************** joints + motors ******************************** */
146 
147 int AbstractKatana::getJointIndex(std::string joint_name)
148 {
149  for (int i = 0; i < (int)joint_names_.size(); i++)
150  {
151  if (joint_names_[i] == joint_name)
152  return i;
153  }
154 
155  for (int i = 0; i < (int)gripper_joint_names_.size(); i++)
156  {
157  if (gripper_joint_names_[i] == joint_name)
158  return GRIPPER_INDEX;
159  }
160 
161  ROS_ERROR("Joint not found: %s.", joint_name.c_str());
162  return -1;
163 }
164 
165 std::vector<std::string> AbstractKatana::getJointNames()
166 {
167  return joint_names_;
168 }
169 
171 {
172  return joint_types_;
173 }
174 
175 std::vector<std::string> AbstractKatana::getGripperJointNames()
176 {
177  return gripper_joint_names_;
178 }
179 
181 {
182  return gripper_joint_types_;
183 }
184 
185 std::vector<double> AbstractKatana::getMotorAngles()
186 {
187  return motor_angles_;
188 }
189 
191 {
192  return motor_velocities_;
193 }
194 
195 std::vector<moveit_msgs::JointLimits> AbstractKatana::getMotorLimits()
196 {
197  return motor_limits_;
198 }
199 
200 double AbstractKatana::getMotorLimitMax(std::string joint_name)
201 {
202  for (size_t i = 0; i < motor_limits_.size(); i++)
203  {
204  if (motor_limits_[i].joint_name == joint_name)
205  {
206  return motor_limits_[i].max_position;
207  }
208  }
209 
210  return -1;
211 }
212 
213 double AbstractKatana::getMotorLimitMin(std::string joint_name)
214 {
215  for (size_t i = 0; i < motor_limits_.size(); i++)
216  {
217  if (motor_limits_[i].joint_name == joint_name)
218  {
219  return motor_limits_[i].min_position;
220  }
221  }
222 
223  return -1;
224 }
225 
226 }
virtual std::vector< std::string > getJointNames()
virtual int getJointIndex(std::string joint_name)
#define ROS_FATAL(...)
URDF_EXPORT bool initString(const std::string &xmlstring)
virtual double getMotorLimitMin(std::string joint_name)
int size() const
std::vector< double > motor_angles_
std::vector< int > joint_types_
const size_t NUM_MOTORS
The number of motors in the katana (= all 5 "real" joints + the gripper)
std::vector< int > gripper_joint_types_
virtual std::vector< int > getGripperJointTypes()
std::vector< double > motor_velocities_
Type const & getType() const
std::vector< std::string > joint_names_
const size_t NUM_GRIPPER_JOINTS
The number of gripper_joints in the katana (= the two gripper finger joints)
std::vector< moveit_msgs::JointLimits > motor_limits_
virtual std::vector< std::string > getGripperJointNames()
virtual std::vector< double > getMotorVelocities()
virtual std::vector< double > getMotorAngles()
const std::string & getNamespace() const
virtual void freezeRobot()
std::vector< std::string > gripper_joint_names_
bool getParam(const std::string &key, std::string &s) const
virtual std::vector< int > getJointTypes()
virtual void refreshMotorStatus()
virtual double getMotorLimitMax(std::string joint_name)
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)
virtual std::vector< moveit_msgs::JointLimits > getMotorLimits()
const size_t GRIPPER_INDEX
The motor index of the gripper (used in all vectors – e.g., motor_angles_)
#define ROS_ERROR(...)


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