wrist_transmission.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 /*
35  * Author: Melonee Wise
36  */
37 #include <math.h>
41 
42 using namespace pr2_mechanism_model;
43 using namespace pr2_hardware_interface;
44 
47 
48 
49 static bool convertDouble(const char* val_str, double &value)
50 {
51  char *endptr=NULL;
52  value = strtod(val_str, &endptr);
53  if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
54  {
55  return false;
56  }
57 
58  return true;
59 }
60 
62 {
63  joint_offset_[0] = 0.0;
64  joint_offset_[1] = 0.0;
65 }
66 
67 
68 bool WristTransmission::initXml(TiXmlElement *elt, Robot *robot)
69 {
70  const char *name = elt->Attribute("name");
71  name_ = name ? name : "";
72 
73 
74  TiXmlElement *ael = elt->FirstChildElement("rightActuator");
75  const char *actuator_name = ael ? ael->Attribute("name") : NULL;
76  Actuator *a;
77  if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
78  {
79  ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
80  return false;
81  }
82  a->command_.enable_ = true;
83  actuator_names_.push_back(actuator_name);
84  const char *act_red = ael->Attribute("mechanicalReduction");
85  if (!act_red)
86  {
87  ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
88  return false;
89  }
90  actuator_reduction_.push_back(atof(act_red));
91 
92  ael = elt->FirstChildElement("leftActuator");
93  actuator_name = ael ? ael->Attribute("name") : NULL;
94  if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
95  {
96  ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
97  return false;
98  }
99  a->command_.enable_ = true;
100  actuator_names_.push_back(actuator_name);
101  act_red = ael->Attribute("mechanicalReduction");
102  if (!act_red)
103  {
104  ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
105  return false;
106  }
107  actuator_reduction_.push_back(atof(act_red));
108 
109 
110  TiXmlElement *j = elt->FirstChildElement("flexJoint");
111  const char *joint_name = j->Attribute("name");
112  if (!joint_name)
113  {
114  ROS_ERROR("WristTransmission did not specify joint name");
115  return false;
116  }
117 #if URDFDOM_1_0_0_API
118  urdf::JointConstSharedPtr joint = robot->robot_model_.getJoint(joint_name);
119 #else
120  const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
121 #endif
122 
123  if (!joint)
124  {
125  ROS_ERROR("WristTransmission could not find joint named \"%s\"", joint_name);
126  return false;
127  }
128  joint_names_.push_back(joint_name);
129  const char *joint_red = j->Attribute("mechanicalReduction");
130  if (!joint_red)
131  {
132  ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
133  return false;
134  }
135  joint_reduction_.push_back(atof(joint_red));
136  const char *joint_offset = j->Attribute("offset");
137  if (!joint_offset)
138  {
139  joint_offset_[0] = 0.0;
140  }
141  else
142  {
143  if (!convertDouble(joint_offset, joint_offset_[0]))
144  {
145  ROS_WARN("WristTransmission's joint \"%s\", cannot convert jointOffset attribute \"%s\" to floating point.",
146  joint_name, joint_offset);
147  return false;
148  }
149  else
150  {
151  ROS_WARN("Joint offset of %f for joint %s.", joint_offset_[0], joint_name);
152  }
153  }
154 
155  j = elt->FirstChildElement("rollJoint");
156  joint_name = j->Attribute("name");
157  if (!joint_name)
158  {
159  ROS_ERROR("WristTransmission did not specify joint name");
160  return false;
161  }
162 #if URDFDOM_1_0_0_API
163  urdf::JointConstSharedPtr joint2 = robot->robot_model_.getJoint(joint_name);
164 #else
165  const boost::shared_ptr<const urdf::Joint> joint2 = robot->robot_model_.getJoint(joint_name);
166 #endif
167 
168  if (!joint2)
169  {
170  ROS_ERROR("WristTransmission could not find joint named \"%s\"", joint_name);
171  return false;
172  }
173  joint_names_.push_back(joint_name);
174  joint_red = j->Attribute("mechanicalReduction");
175  if (!joint_red)
176  {
177  ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
178  return false;
179  }
180  joint_reduction_.push_back(atof(joint_red));
181  joint_offset = j->Attribute("offset");
182  if (!joint_offset)
183  {
184  joint_offset_[1] = 0.0;
185  }
186  else
187  {
188  if (!convertDouble(joint_offset, joint_offset_[1]))
189  {
190  ROS_WARN("WristTransmission's joint \"%s\", cannot convert jointOffset attribute \"%s\" to floating point.",
191  joint_name, joint_offset);
192  return false;
193  }
194  else
195  {
196  ROS_WARN("Joint offset of %f for joint %s.", joint_offset_[1], joint_name);
197  }
198  }
199 
200 
201  return true;
202 }
203 
204 bool WristTransmission::initXml(TiXmlElement *elt)
205 {
206  const char *name = elt->Attribute("name");
207  name_ = name ? name : "";
208 
209 
210  TiXmlElement *ael = elt->FirstChildElement("rightActuator");
211  const char *actuator_name = ael ? ael->Attribute("name") : NULL;
212  if (!actuator_name)
213  {
214  ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
215  return false;
216  }
217  actuator_names_.push_back(actuator_name);
218  const char *act_red = ael->Attribute("mechanicalReduction");
219  if (!act_red)
220  {
221  ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
222  return false;
223  }
224  actuator_reduction_.push_back(atof(act_red));
225 
226  ael = elt->FirstChildElement("leftActuator");
227  actuator_name = ael ? ael->Attribute("name") : NULL;
228  if (!actuator_name)
229  {
230  ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
231  return false;
232  }
233  actuator_names_.push_back(actuator_name);
234  act_red = ael->Attribute("mechanicalReduction");
235  if (!act_red)
236  {
237  ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
238  return false;
239  }
240  actuator_reduction_.push_back(atof(act_red));
241 
242 
243  TiXmlElement *j = elt->FirstChildElement("flexJoint");
244  const char *joint_name = j->Attribute("name");
245  if (!joint_name)
246  {
247  ROS_ERROR("WristTransmission did not specify joint name");
248  return false;
249  }
250  joint_names_.push_back(joint_name);
251  const char *joint_red = j->Attribute("mechanicalReduction");
252  if (!joint_red)
253  {
254  ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
255  return false;
256  }
257  joint_reduction_.push_back(atof(joint_red));
258  const char *joint_offset = j->Attribute("offset");
259  if (!joint_offset)
260  {
261  joint_offset_[0] = 0.0;
262  }
263  else
264  {
265  double offset;
266  if (!convertDouble(joint_offset, joint_offset_[0]))
267  {
268  ROS_WARN("WristTransmission's joint \"%s\", cannot convert jointOffset attribute \"%s\" to floating point.",
269  joint_name, joint_offset);
270  return false;
271  }
272  else
273  {
274  ROS_WARN("Joint offset of %f for joint %s.", joint_offset_[0], joint_name);
275  }
276  }
277 
278  j = elt->FirstChildElement("rollJoint");
279  joint_name = j->Attribute("name");
280  if (!joint_name)
281  {
282  ROS_ERROR("WristTransmission did not specify joint name");
283  return false;
284  }
285  joint_names_.push_back(joint_name);
286  joint_red = j->Attribute("mechanicalReduction");
287  if (!joint_red)
288  {
289  ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
290  return false;
291  }
292  joint_reduction_.push_back(atof(joint_red));
293  if (!joint_offset)
294  {
295  joint_offset_[1] = 0.0;
296  }
297  else
298  {
299  if (!convertDouble(joint_offset, joint_offset_[1]))
300  {
301  ROS_WARN("WristTransmission's joint \"%s\", cannot convert jointOffset attribute \"%s\" to floating point.",
302  joint_name, joint_offset);
303  return false;
304  }
305  else
306  {
307  ROS_WARN("Joint offset of %f for joint %s.", joint_offset_[1], joint_name);
308  }
309  }
310 
311  return true;
312 }
313 
315  std::vector<Actuator*>& as, std::vector<JointState*>& js)
316 {
317  assert(as.size() == 2);
318  assert(js.size() == 2);
319 
320  js[0]->position_ = ((as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/
321  (2*joint_reduction_[0])) + js[0]->reference_position_+joint_offset_[0];
322  js[0]->velocity_ = (as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[0]);
323  js[0]->measured_effort_ = joint_reduction_[0]*(as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
324 
325  js[1]->position_ = ((-as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/
326  (2*joint_reduction_[1]))+js[1]->reference_position_+joint_offset_[1];
327  js[1]->velocity_ = (-as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[1]);
328  js[1]->measured_effort_ = joint_reduction_[1]*(-as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
329 }
330 
332  std::vector<JointState*>& js, std::vector<Actuator*>& as)
333 {
334  assert(as.size() == 2);
335  assert(js.size() == 2);
336 
337  as[0]->state_.position_ = (((js[0]->position_-js[0]->reference_position_-joint_offset_[0])*joint_reduction_[0] -
338  (js[1]->position_-js[1]->reference_position_-joint_offset_[1])*joint_reduction_[1]) * actuator_reduction_[0]);
339  as[0]->state_.velocity_ = ((js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[0]);
340  as[0]->state_.last_measured_effort_ = (js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
341 
342  as[1]->state_.position_ = ((-(js[0]->position_-js[0]->reference_position_-joint_offset_[0])*joint_reduction_[0] -
343  (js[1]->position_-js[1]->reference_position_-joint_offset_[1])*joint_reduction_[1]) * actuator_reduction_[1]);
344  as[1]->state_.velocity_ = ((-js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[1]);
345  as[1]->state_.last_measured_effort_ = (-js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
346 
347  // Update the timing (making sure it's initialized).
348  if (! simulated_actuator_timestamp_initialized_)
349  {
350  // Set the time stamp to zero (it is measured relative to the start time).
351  as[0]->state_.sample_timestamp_ = ros::Duration(0);
352  as[1]->state_.sample_timestamp_ = ros::Duration(0);
353 
354  // Try to set the start time. Only then do we claim initialized.
355  if (ros::isStarted())
356  {
357  simulated_actuator_start_time_ = ros::Time::now();
358  simulated_actuator_timestamp_initialized_ = true;
359  }
360  }
361  else
362  {
363  // Measure the time stamp relative to the start time.
364  as[0]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
365  as[1]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
366  }
367  // Set the historical (double) timestamp accordingly.
368  as[0]->state_.timestamp_ = as[0]->state_.sample_timestamp_.toSec();
369  as[1]->state_.timestamp_ = as[1]->state_.sample_timestamp_.toSec();
370 
371  // simulate calibration sensors by filling out actuator states
372  // this is where to embed the hack which joint connects to which mcb
373  this->joint_calibration_simulator_[0].simulateJointCalibration(js[0],as[1]);
374  this->joint_calibration_simulator_[1].simulateJointCalibration(js[1],as[0]);
375 }
376 
378  std::vector<JointState*>& js, std::vector<Actuator*>& as)
379 {
380  assert(as.size() == 2);
381  assert(js.size() == 2);
382 
383  as[0]->command_.enable_ = true;
384  as[1]->command_.enable_ = true;
385 
386  as[0]->command_.effort_ = (js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
387  as[1]->command_.effort_ = (-js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
388 }
389 
391  std::vector<Actuator*>& as, std::vector<JointState*>& js)
392 {
393  assert(as.size() == 2);
394  assert(js.size() == 2);
395 
396  js[0]->commanded_effort_ = joint_reduction_[0]*(as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
397  js[1]->commanded_effort_ = joint_reduction_[1]*(-as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
398 }
399 
400 
401 void WristTransmission::setReductions(std::vector<double>& ar, std::vector<double>& jr)
402 {
403  actuator_reduction_ = ar;
404  joint_reduction_ = jr;
405 }
406 
#define ROS_ERROR(...)
void propagatePositionBackwards(std::vector< pr2_mechanism_model::JointState *> &, std::vector< pr2_hardware_interface::Actuator *> &)
Uses the joint position to fill out the actuator&#39;s encoder.
#define ROS_WARN(...)
pr2_hardware_interface::Actuator * getActuator(const std::string &name) const
get an actuator pointer based on the actuator name. Returns NULL on failure
Definition: robot.cpp:143
void propagateEffortBackwards(std::vector< pr2_hardware_interface::Actuator *> &, std::vector< pr2_mechanism_model::JointState *> &)
Uses the actuator&#39;s commanded effort to fill out the torque on the joint.
void propagatePosition(std::vector< pr2_hardware_interface::Actuator *> &, std::vector< pr2_mechanism_model::JointState *> &)
Uses encoder data to fill out joint position and velocities.
void propagateEffort(std::vector< pr2_mechanism_model::JointState *> &, std::vector< pr2_hardware_interface::Actuator *> &)
Uses commanded joint efforts to fill out commanded motor currents.
bool initXml(TiXmlElement *config, Robot *robot)
Initializes the transmission from XML data.
ROSCPP_DECL bool isStarted()
static Time now()
double & value
void setReductions(std::vector< double > &ar, std::vector< double > &jr)
This class provides the controllers with an interface to the robot model.
Definition: robot.h:78
urdf::Model robot_model_
The kinematic/dynamic model of the robot.
Definition: robot.h:91
PLUGINLIB_EXPORT_CLASS(pr2_mechanism_model::WristTransmission, pr2_mechanism_model::Transmission) static bool convertDouble(const char *val_str


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Tue Mar 7 2023 03:54:53