mia_hand_ros_control  rel 1.0.0
mia_mrl_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 interfae of the MIA mrl fingers
30 
31  version 1.0
32 
33 **********************************************************************************************************/
34 
35 
36  #ifndef TRANSMISSION_INTERFACE_MIA_MRL_TRANSMISSION_H
37  #define TRANSMISSION_INTERFACE_MIA_MRL_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 MiaMrlTransmission : public Transmission
55  {
56  public:
57 
62 
66  void actuatorToJointEffort(const transmission_interface::ActuatorData& act_data,
67  transmission_interface::JointData& jnt_data);
68 
74  void actuatorToJointVelocity(const transmission_interface::ActuatorData& act_data,
75  transmission_interface::JointData& jnt_data);
81  void actuatorToJointPosition(const transmission_interface::ActuatorData& act_data,
82  transmission_interface::JointData& jnt_data);
83 
87  void jointToActuatorEffort(const transmission_interface::JointData& jnt_data,
88  transmission_interface::ActuatorData& act_data);
89 
95  void jointToActuatorVelocity(const transmission_interface::JointData& jnt_data,
96  transmission_interface::ActuatorData& act_data);
97 
103  void jointToActuatorPosition(const transmission_interface::JointData& jnt_data,
104  transmission_interface::ActuatorData& act_data);
105 
106  // Functions describing the mrl trasmissions steps
107 
113  double h_mrl(const double pos); // mu = h_mrl(pos)
114 
120  double h_mrl_inv(const double mu); // pos = h_mrl_inv(mu)
121 
127  double dh(const double spe); // omega_m = dh(spe)
128 
134  double dh_inv(const double omega_m); // spe = dh_inv(omega_m) return round
135 
136 
137  std::size_t numActuators() const {return 1;}
138  std::size_t numJoints() const {return 1;}
139 
140 
141  double getActuatorReduction() const {return reduction_;}
142  double getJointOffset() const {return jnt_offset_;}
143 
144  private:
145  double reduction_;
146  double jnt_offset_;
147  };
148 
149 
150  } // transmission_interface
151 
152  #endif // MIA_MRL_TRANSMISSION_H
transmission_interface::MiaMrlTransmission::getJointOffset
double getJointOffset() const
Definition: mia_mrl_transmission.h:154
transmission_interface::MiaMrlTransmission::getActuatorReduction
double getActuatorReduction() const
Definition: mia_mrl_transmission.h:153
transmission_interface::MiaMrlTransmission::actuatorToJointVelocity
void actuatorToJointVelocity(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform velocity variables from actuator to joint space.
Definition: mia_mrl_transmission.cpp:84
transmission_interface::MiaMrlTransmission::dh
double dh(const double spe)
Mrl transmission first step function for velocity: pos = omega_m = dh(spe).
Definition: mia_mrl_transmission.cpp:60
transmission_interface::MiaMrlTransmission::dh_inv
double dh_inv(const double omega_m)
Mrl transmission first step inverse function for velocity: spe = dh_inv(omega_m).
Definition: mia_mrl_transmission.cpp:69
transmission_interface
Definition: mia_index_transmission.h:23
transmission_interface::MiaMrlTransmission::h_mrl
double h_mrl(const double pos)
Mrl transmission first step function for pose: mu = mu = h_mrl(pos).
Definition: mia_mrl_transmission.cpp:42
transmission_interface::MiaMrlTransmission::actuatorToJointPosition
void actuatorToJointPosition(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform position variables from actuator to joint space.
Definition: mia_mrl_transmission.cpp:95
transmission_interface::MiaMrlTransmission::MiaMrlTransmission
MiaMrlTransmission()
Class constructor.
Definition: mia_mrl_transmission.cpp:23
transmission_interface::MiaMrlTransmission::h_mrl_inv
double h_mrl_inv(const double mu)
Mrl transmission first step inverse function for pose: pos = h_mrl_inv(mu).
Definition: mia_mrl_transmission.cpp:51
transmission_interface::MiaMrlTransmission::jointToActuatorVelocity
void jointToActuatorVelocity(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform velocity variables from joint to actuator space.
Definition: mia_mrl_transmission.cpp:106
transmission_interface::MiaMrlTransmission::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_mrl_transmission.cpp:139
transmission_interface::MiaMrlTransmission::jointToActuatorPosition
void jointToActuatorPosition(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform position variables from joint to actuator space.
Definition: mia_mrl_transmission.cpp:117
transmission_interface::MiaMrlTransmission::jnt_offset_
double jnt_offset_
Offset of teh joint.
Definition: mia_mrl_transmission.h:158
transmission_interface::MiaMrlTransmission::reduction_
double reduction_
Linear second step reduction of the tranmission.
Definition: mia_mrl_transmission.h:157
transmission_interface::MiaMrlTransmission::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_mrl_transmission.cpp:132