wrist_transmission.h
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  example xml:
38  <robot name="wrist_trans">
39  <joint name="right_wrist_flex_joint" type="revolute">
40  <limit min="-0.157" max="2.409" effort="5" velocity="5" />
41  <axis xyz="0 0 1" />
42  </joint>
43 
44  <joint name="right_wrist_roll_joint" type="continuous">
45  <limit min="0.0" max="0.0" effort="5" velocity="5" />
46  <axis xyz="0 0 1" />
47  </joint>
48 
49  <transmission type="WristTransmission" name="wrist_trans">
50  <rightActuator name="right_wrist_r_motor" mechanicalReduction="60.17"/>
51  <leftActuator name="right_wrist_l_motor" mechanicalReduction="60.17"/>
52  <flexJoint name="wrist_right_flex_joint" mechanicalReduction="1"/>
53  <rollJoint name="wrist_right_roll_joint" mechanicalReduction="1"/>
54  </transmission>
55  </robot>
56  */
57 #ifndef WRIST_TRANSMISSION_H
58 #define WRIST_TRANSMISSION_H
59 
60 #include <tinyxml.h>
65 
66 namespace pr2_mechanism_model {
67 
69 {
70 public:
73 
74  bool initXml(TiXmlElement *config, Robot *robot);
75  bool initXml(TiXmlElement *config);
76 
77  std::vector<double> actuator_reduction_;
78  std::vector<double> joint_reduction_;
79  double joint_offset_[2];
80 
81  // Describes the order of the actuators and the joints in the arrays
82  // of names and of those passed to propagate*
85 
86  void propagatePosition(std::vector<pr2_hardware_interface::Actuator*>&,
87  std::vector<pr2_mechanism_model::JointState*>&);
88  void propagatePositionBackwards(std::vector<pr2_mechanism_model::JointState*>&,
89  std::vector<pr2_hardware_interface::Actuator*>&);
90  void propagateEffort(std::vector<pr2_mechanism_model::JointState*>&,
91  std::vector<pr2_hardware_interface::Actuator*>&);
92  void propagateEffortBackwards(std::vector<pr2_hardware_interface::Actuator*>&,
93  std::vector<pr2_mechanism_model::JointState*>&);
94  void setReductions(std::vector<double>& ar, std::vector<double>& jr);
95 
96 private:
99 
101 };
102 
103 } // namespace pr2_mechanism_model
104 
105 #endif
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.
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.
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
JointCalibrationSimulator joint_calibration_simulator_[2]


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