mia_hand_ros_control
rel 1.0.0
|
Go to the documentation of this file.
36 #ifndef TRANSMISSION_INTERFACE_MIA_MRL_TRANSMISSION_H
37 #define TRANSMISSION_INTERFACE_MIA_MRL_TRANSMISSION_H
43 #include <transmission_interface/transmission.h>
44 #include <transmission_interface/transmission_interface_exception.h>
54 class MiaMrlTransmission :
public Transmission
67 transmission_interface::JointData& jnt_data);
75 transmission_interface::JointData& jnt_data);
82 transmission_interface::JointData& jnt_data);
88 transmission_interface::ActuatorData& act_data);
96 transmission_interface::ActuatorData& act_data);
104 transmission_interface::ActuatorData& act_data);
113 double h_mrl(
const double pos);
127 double dh(
const double spe);
134 double dh_inv(
const double omega_m);
137 std::size_t numActuators()
const {
return 1;}
138 std::size_t numJoints()
const {
return 1;}
152 #endif // MIA_MRL_TRANSMISSION_H
double getJointOffset() const
double getActuatorReduction() const
void actuatorToJointVelocity(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform velocity variables from actuator to joint space.
double dh(const double spe)
Mrl transmission first step function for velocity: pos = omega_m = dh(spe).
double dh_inv(const double omega_m)
Mrl transmission first step inverse function for velocity: spe = dh_inv(omega_m).
double h_mrl(const double pos)
Mrl transmission first step function for pose: mu = mu = h_mrl(pos).
void actuatorToJointPosition(const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
Transform position variables from actuator to joint space.
MiaMrlTransmission()
Class constructor.
double h_mrl_inv(const double mu)
Mrl transmission first step inverse function for pose: pos = h_mrl_inv(mu).
void jointToActuatorVelocity(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform velocity variables from joint to actuator space.
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.
void jointToActuatorPosition(const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
Transform position variables from joint to actuator space.
double jnt_offset_
Offset of teh joint.
double reduction_
Linear second step reduction of the tranmission.
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.