pr2_gripper_transmission.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * <transmission type="PR2GripperTransmission" name="gripper_l_transmission">
32  * <actuator name="l_gripper_motor" />
33  * <gap_joint name="l_gripper_joint" mechanical_reduction="1.0" A="0.05" B="1.0" C="0.0" />
34  * <passive_joint name="l_gripper_l_finger_joint" />
35  * <passive_joint name="l_gripper_r_finger_joint" />
36  * <passive_joint name="l_gripper_r_finger_tip_joint" />
37  * <passive_joint name="l_gripper_l_finger_tip_joint" />
38  * </transmission>
39  *
40  * Author: John Hsu
41  */
42 
43 #ifndef GRIPPER_TRANSMISSION_H
44 #define GRIPPER_TRANSMISSION_H
45 
46 #include <vector>
47 #include "tinyxml.h"
50 //#include <fstream>
52 
53 namespace pr2_mechanism_model {
54 
56 {
57 public:
59  virtual ~PR2GripperTransmission() {/*myfile.close();*/}
60 
61  bool initXml(TiXmlElement *config, Robot *robot);
62  bool initXml(TiXmlElement *config);
63 
64  void propagatePosition(std::vector<pr2_hardware_interface::Actuator*>&,
65  std::vector<pr2_mechanism_model::JointState*>&);
66  void propagatePositionBackwards(std::vector<pr2_mechanism_model::JointState*>&,
67  std::vector<pr2_hardware_interface::Actuator*>&);
68  void propagateEffort(std::vector<pr2_mechanism_model::JointState*>&,
69  std::vector<pr2_hardware_interface::Actuator*>&);
70  void propagateEffortBackwards(std::vector<pr2_hardware_interface::Actuator*>&,
71  std::vector<pr2_mechanism_model::JointState*>&);
72  std::string gap_joint_;
73  //
74  // per Functions Engineering doc, 090224_link_data.xml,
75  // here, gap_mechanical_reduction_ transforms FROM ENCODER VALUE TO MOTOR REVOLUTIONS
76  //
78 
79  // if a screw_joint is specified, apply torque based on simulated_reduction_
83 
84  // The joint_names_ variable is inherited from Transmission. In
85  // joint_names_, the gap joint is first, followed by all the passive
86  // joints.
87 
88  // store name for passive joints. This matches elements 1 to N of joint_names_.
89  std::vector<std::string> passive_joints_;
90 
91 private:
93  void computeGapStates(double MR,double MR_dot,double MT,
94  double &theta,double &dtheta_dMR,double &dt_dtheta,double &dt_dMR,double &gap_size,double &gap_velocity,double &gap_effort);
95  void inverseGapStates(double gap_size,double &MR, double &dMR_dtheta,double &dtheta_dt,double &dMR_dt);
96  void inverseGapStates1(double theta,double &MR, double &dMR_dtheta,double &dtheta_dt,double &dMR_dt);
97 
98  //
99  // SOME CONSTANTS
100  // the default theta0 when gap size is 0 is needed to assign passive joint angles
101  //
102  double screw_reduction_; // default for alpha2 = 2.0/1000.0; //in meters/revolution
103  double gear_ratio_ ; // default for alpha2 = 29.16; // is a ratio
104  double theta0_ ; // default for alpha2 = 2.97571*M_PI/180.0; // convert to radians
105  double phi0_ ; // default for alpha2 = 29.98717*M_PI/180.0; // convert to radians
106  double t0_ ; // default for alpha2 = 0; //-0.19543/1000.0; // convert to meters
107  double L0_ ; // default for alpha2 = 34.70821/1000.0; // convert to meters
108  double h_ ; // default for alpha2 = 5.200/1000.0; // convert to meters
109  double a_ ; // default for alpha2 = 67.56801/1000.0; // convert to meters
110  double b_ ; // default for alpha2 = 48.97193/1000.0; // convert to meters
111  double r_ ; // default for alpha2 = 91.50000/1000.0; // convert to meters
112 
113 #define RAD2MR (1.0/(2.0*M_PI)) // convert radians to motor revolutions
114 #define TOL 0.00001 // limit for denominators
115 
118 
120 };
121 
122 } // namespace pr2_mechanism_model
123 
124 #endif
pr2_mechanism_model::PR2GripperTransmission::gap_joint_
std::string gap_joint_
Definition: pr2_gripper_transmission.h:72
robot.h
pr2_mechanism_model::PR2GripperTransmission::b_
double b_
Definition: pr2_gripper_transmission.h:110
pr2_mechanism_model::PR2GripperTransmission::inverseGapStates1
void inverseGapStates1(double theta, double &MR, double &dMR_dtheta, double &dtheta_dt, double &dMR_dt)
Definition: pr2_gripper_transmission.cpp:494
pr2_mechanism_model::PR2GripperTransmission::simulated_actuator_start_time_
ros::Time simulated_actuator_start_time_
Definition: pr2_gripper_transmission.h:117
pr2_mechanism_model::PR2GripperTransmission::use_simulated_actuated_joint_
bool use_simulated_actuated_joint_
Definition: pr2_gripper_transmission.h:81
pr2_mechanism_model
Definition: chain.h:41
pr2_mechanism_model::Transmission
Definition: transmission.h:80
pr2_mechanism_model::PR2GripperTransmission::PR2GripperTransmission
PR2GripperTransmission()
Definition: pr2_gripper_transmission.h:58
pr2_mechanism_model::PR2GripperTransmission::theta0_
double theta0_
Definition: pr2_gripper_transmission.h:104
pr2_mechanism_model::PR2GripperTransmission::screw_reduction_
double screw_reduction_
Definition: pr2_gripper_transmission.h:102
pr2_mechanism_model::PR2GripperTransmission::inverseGapStates
void inverseGapStates(double gap_size, double &MR, double &dMR_dtheta, double &dtheta_dt, double &dMR_dt)
Definition: pr2_gripper_transmission.cpp:478
pr2_mechanism_model::PR2GripperTransmission::propagateEffortBackwards
void propagateEffortBackwards(std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &)
Uses the actuator's commanded effort to fill out the torque on the joint.
Definition: pr2_gripper_transmission.cpp:710
pr2_mechanism_model::PR2GripperTransmission::simulated_reduction_
double simulated_reduction_
Definition: pr2_gripper_transmission.h:80
pr2_mechanism_model::PR2GripperTransmission::L0_
double L0_
Definition: pr2_gripper_transmission.h:107
pr2_mechanism_model::PR2GripperTransmission::gear_ratio_
double gear_ratio_
Definition: pr2_gripper_transmission.h:103
pr2_mechanism_model::PR2GripperTransmission::simulated_actuator_timestamp_initialized_
int simulated_actuator_timestamp_initialized_
Definition: pr2_gripper_transmission.h:116
pr2_mechanism_model::PR2GripperTransmission::passive_joints_
std::vector< std::string > passive_joints_
Definition: pr2_gripper_transmission.h:89
pr2_mechanism_model::PR2GripperTransmission::r_
double r_
Definition: pr2_gripper_transmission.h:111
pr2_mechanism_model::PR2GripperTransmission::has_simulated_passive_actuated_joint_
bool has_simulated_passive_actuated_joint_
Definition: pr2_gripper_transmission.h:82
pr2_mechanism_model::PR2GripperTransmission::gap_mechanical_reduction_
double gap_mechanical_reduction_
Definition: pr2_gripper_transmission.h:77
pr2_mechanism_model::PR2GripperTransmission::propagatePositionBackwards
void propagatePositionBackwards(std::vector< pr2_mechanism_model::JointState * > &, std::vector< pr2_hardware_interface::Actuator * > &)
Uses the joint position to fill out the actuator's encoder.
Definition: pr2_gripper_transmission.cpp:616
transmission.h
pr2_mechanism_model::Robot
This class provides the controllers with an interface to the robot model.
Definition: robot.h:78
pr2_mechanism_model::PR2GripperTransmission::~PR2GripperTransmission
virtual ~PR2GripperTransmission()
Definition: pr2_gripper_transmission.h:59
pr2_mechanism_model::JointCalibrationSimulator
Definition: joint_calibration_simulator.h:42
pr2_mechanism_model::PR2GripperTransmission::phi0_
double phi0_
Definition: pr2_gripper_transmission.h:105
pr2_mechanism_model::PR2GripperTransmission::a_
double a_
Definition: pr2_gripper_transmission.h:109
ros::Time
pr2_mechanism_model::PR2GripperTransmission::computeGapStates
void computeGapStates(double MR, double MR_dot, double MT, double &theta, double &dtheta_dMR, double &dt_dtheta, double &dt_dMR, double &gap_size, double &gap_velocity, double &gap_effort)
compute gap position, velocity and measured effort from actuator states
Definition: pr2_gripper_transmission.cpp:421
pr2_mechanism_model::PR2GripperTransmission::initXml
bool initXml(TiXmlElement *config, Robot *robot)
Initializes the transmission from XML data.
pr2_mechanism_model::PR2GripperTransmission::h_
double h_
Definition: pr2_gripper_transmission.h:108
pr2_mechanism_model::PR2GripperTransmission
Definition: pr2_gripper_transmission.h:55
pr2_mechanism_model::PR2GripperTransmission::propagatePosition
void propagatePosition(std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &)
Definition: pr2_gripper_transmission.cpp:537
joint_calibration_simulator.h
pr2_mechanism_model::PR2GripperTransmission::propagateEffort
void propagateEffort(std::vector< pr2_mechanism_model::JointState * > &, std::vector< pr2_hardware_interface::Actuator * > &)
Uses commanded joint efforts to fill out commanded motor currents.
Definition: pr2_gripper_transmission.cpp:679
pr2_mechanism_model::PR2GripperTransmission::t0_
double t0_
Definition: pr2_gripper_transmission.h:106
pr2_mechanism_model::PR2GripperTransmission::joint_calibration_simulator_
JointCalibrationSimulator joint_calibration_simulator_
Definition: pr2_gripper_transmission.h:119


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Mon Mar 6 2023 03:49:17