mia_hand_ros_control  rel 1.0.0
mia_thfle_transmission.h
Go to the documentation of this file.
1  // Copyright (C) 2013, PAL Robotics S.L.
2  //
3  // Redistribution and use in source and binary forms, with or without
4  // modification, are permitted provided that the following conditions are met:
5  // * Redistributions of source code must retain the above copyright notice,
6  // this list of conditions and the following disclaimer.
7  // * Redistributions in binary form must reproduce the above copyright
8  // notice, this list of conditions and the following disclaimer in the
9  // documentation and/or other materials provided with the distribution.
10  // * Neither the name of PAL Robotics S.L. nor the names of its
11  // contributors may be used to endorse or promote products derived from
12  // this software without specific prior written permission.
13  //
14  // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15  // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16  // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17  // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
18  // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19  // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20  // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21  // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22  // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23  // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24  // POSSIBILITY OF SUCH DAMAGE.
25 
26 
27  /*********************************************************************************************************
28  Modifyed by Author: Prensilia srl
29  Desc: Transmission interface of the MIA thumb flexion finger
30 
31  version 1.0
32 
33 **********************************************************************************************************/
34 
35 
36  #ifndef TRANSMISSION_INTERFACE_MIA_THFLE_TRANSMISSION_H
37  #define TRANSMISSION_INTERFACE_MIA_THFLE_TRANSMISSION_H
38 
39  #include <cassert>
40  #include <string>
41  #include <vector>
42 
43  #include <transmission_interface/transmission.h>
44  #include <transmission_interface/transmission_interface_exception.h>
45 
46  namespace transmission_interface
47  {
48 
54  class MiaThfleTransmission : public Transmission
55  {
56  public:
57 
62 
63 
67  void actuatorToJointEffort(const transmission_interface::ActuatorData& act_data,
68  transmission_interface::JointData& jnt_data);
69 
75  void actuatorToJointVelocity(const transmission_interface::ActuatorData& act_data,
76  transmission_interface::JointData& jnt_data);
77 
83  void actuatorToJointPosition(const transmission_interface::ActuatorData& act_data,
84  transmission_interface::JointData& jnt_data);
85 
89  void jointToActuatorEffort(const transmission_interface::JointData& jnt_data,
90  transmission_interface::ActuatorData& act_data);
91 
97  void jointToActuatorVelocity(const transmission_interface::JointData& jnt_data,
98  transmission_interface::ActuatorData& act_data);
99 
105  void jointToActuatorPosition(const transmission_interface::JointData& jnt_data,
106  transmission_interface::ActuatorData& act_data);
107 
108  // Functions describing the mrl trasmissions steps
109 
115  double h_thfle(const double pos); // mu = h_thfle(pos)
116 
122  double h_thfle_inv(const double mu); // pos = h_thfle_inv(mu)
123 
129  double dh(const double spe); // omega_m = dh(spe)
130 
131 
137  double dh_inv(const double omega_m); // spe = dh_inv(omega_m)
138 
139 
140  std::size_t numActuators() const {return 1;}
141  std::size_t numJoints() const {return 1;}
142 
143 
144  double getActuatorReduction() const {return reduction_;}
145  double getJointOffset() const {return jnt_offset_;}
146 
147  private:
148  double reduction_;
149  double jnt_offset_;
150  };
151 
152 
153  } // transmission_interface
154 
155  #endif // MIA_THFLE_TRANSMISSION_H
transmission_interface::MiaThfleTransmission::jointToActuatorVelocity
void jointToActuatorVelocity(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform velocity variables from joint to actuator space.
Definition: mia_thfle_transmission.cpp:105
transmission_interface
Definition: mia_index_transmission.h:23
transmission_interface::MiaThfleTransmission::dh_inv
double dh_inv(const double omega_m)
Thumb flexion transmission first step inverse function for velocity: spe = dh_inv(omega_m).
Definition: mia_thfle_transmission.cpp:68
transmission_interface::MiaThfleTransmission::actuatorToJointVelocity
void actuatorToJointVelocity(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform velocity variables from actuator to joint space.
Definition: mia_thfle_transmission.cpp:83
transmission_interface::MiaThfleTransmission::h_thfle_inv
double h_thfle_inv(const double mu)
Thumb flexion transmission first step inverse function for pose: pos = h_thfle_inv(mu).
Definition: mia_thfle_transmission.cpp:50
transmission_interface::MiaThfleTransmission::getJointOffset
double getJointOffset() const
Definition: mia_thfle_transmission.h:157
transmission_interface::MiaThfleTransmission::actuatorToJointPosition
void actuatorToJointPosition(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform position variables from actuator to joint space.
Definition: mia_thfle_transmission.cpp:94
transmission_interface::MiaThfleTransmission::jnt_offset_
double jnt_offset_
Offset of teh joint.
Definition: mia_thfle_transmission.h:161
transmission_interface::MiaThfleTransmission::h_thfle
double h_thfle(const double pos)
Thumb flexion transmission first step function for pose: mu = mu = h_thfle(pos).
Definition: mia_thfle_transmission.cpp:41
transmission_interface::MiaThfleTransmission::actuatorToJointEffort
void actuatorToJointEffort(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Do not use this methos since Mia hand has not effort control.
Definition: mia_thfle_transmission.cpp:131
transmission_interface::MiaThfleTransmission::jointToActuatorPosition
void jointToActuatorPosition(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform position variables from joint to actuator space.
Definition: mia_thfle_transmission.cpp:116
transmission_interface::MiaThfleTransmission::reduction_
double reduction_
Linear second step reduction of the tranmission.
Definition: mia_thfle_transmission.h:160
transmission_interface::MiaThfleTransmission::getActuatorReduction
double getActuatorReduction() const
Definition: mia_thfle_transmission.h:156
transmission_interface::MiaThfleTransmission::dh
double dh(const double spe)
Thumb flexion transmission first step function for velocity: omega_m = dh(spe)
Definition: mia_thfle_transmission.cpp:59
transmission_interface::MiaThfleTransmission::MiaThfleTransmission
MiaThfleTransmission()
Class constructor.
Definition: mia_thfle_transmission.cpp:22
transmission_interface::MiaThfleTransmission::jointToActuatorEffort
void jointToActuatorEffort(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Do not use this methos since Mia hand has not effort control.
Definition: mia_thfle_transmission.cpp:138