mia_hand_ros_control  rel 1.0.0
transmission_interface::MiaMrlTransmission Class Reference

Implementation of the linear Mia mrl Transmission mapping the positions and velocity from the joint sapce to ros actuator-space (i.e. More...

#include <mia_mrl_transmission.h>

Inheritance diagram for transmission_interface::MiaMrlTransmission:
Collaboration diagram for transmission_interface::MiaMrlTransmission:

Public Member Functions

 MiaMrlTransmission ()
 Class constructor. More...
 
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. More...
 
void actuatorToJointVelocity (const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
 Transform velocity variables from actuator to joint space. More...
 
void actuatorToJointPosition (const transmission_interface::ActuatorData &act_data, transmission_interface::JointData &jnt_data)
 Transform position variables from actuator to joint space. More...
 
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. More...
 
void jointToActuatorVelocity (const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
 Transform velocity variables from joint to actuator space. More...
 
void jointToActuatorPosition (const transmission_interface::JointData &jnt_data, transmission_interface::ActuatorData &act_data)
 Transform position variables from joint to actuator space. More...
 
double h_mrl (const double pos)
 Mrl transmission first step function for pose: mu = mu = h_mrl(pos). More...
 
double h_mrl_inv (const double mu)
 Mrl transmission first step inverse function for pose: pos = h_mrl_inv(mu). More...
 
double dh (const double spe)
 Mrl transmission first step function for velocity: pos = omega_m = dh(spe). More...
 
double dh_inv (const double omega_m)
 Mrl transmission first step inverse function for velocity: spe = dh_inv(omega_m). More...
 
double getActuatorReduction () const
 
double getJointOffset () const
 

Private Attributes

double reduction_
 Linear second step reduction of the tranmission. More...
 
double jnt_offset_
 Offset of teh joint. More...
 

Detailed Description

Implementation of the linear Mia mrl Transmission mapping the positions and velocity from the joint sapce to ros actuator-space (i.e.

as returned by Mia hand [-255; +255] and [-90;+90]) and vice-versa.

Definition at line 60 of file mia_mrl_transmission.h.

Constructor & Destructor Documentation

◆ MiaMrlTransmission()

transmission_interface::MiaMrlTransmission::MiaMrlTransmission ( )

Class constructor.

Definition at line 23 of file mia_mrl_transmission.cpp.

Member Function Documentation

◆ actuatorToJointEffort()

void transmission_interface::MiaMrlTransmission::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 at line 132 of file mia_mrl_transmission.cpp.

◆ actuatorToJointPosition()

void transmission_interface::MiaMrlTransmission::actuatorToJointPosition ( const transmission_interface::ActuatorData &  act_data,
transmission_interface::JointData &  jnt_data 
)

Transform position variables from actuator to joint space.

Parameters
act_datamrl actuator actual state.
jnt_datareturned mrl joint state.

Definition at line 95 of file mia_mrl_transmission.cpp.

◆ actuatorToJointVelocity()

void transmission_interface::MiaMrlTransmission::actuatorToJointVelocity ( const transmission_interface::ActuatorData &  act_data,
transmission_interface::JointData &  jnt_data 
)

Transform velocity variables from actuator to joint space.

Parameters
act_datamrl actuator actual state.
jnt_datareturned mrl joint state.

Definition at line 84 of file mia_mrl_transmission.cpp.

◆ dh()

double transmission_interface::MiaMrlTransmission::dh ( const double  spe)

Mrl transmission first step function for velocity: pos = omega_m = dh(spe).

Parameters
speround velocity in the ros actuator-space (i.e. as returned by Mia hand [-90; +90]).
Returns
omega_m velocity in the mia actuator space.

Definition at line 60 of file mia_mrl_transmission.cpp.

◆ dh_inv()

double transmission_interface::MiaMrlTransmission::dh_inv ( const double  omega_m)

Mrl transmission first step inverse function for velocity: spe = dh_inv(omega_m).

Parameters
omega_mvelocity in the mia actuator space.
Returns
spe: round velocity in the ros actuator-space (i.e. as returned by Mia hand [-90; +90]).

Definition at line 69 of file mia_mrl_transmission.cpp.

◆ getActuatorReduction()

double transmission_interface::MiaMrlTransmission::getActuatorReduction ( ) const
inline

Definition at line 153 of file mia_mrl_transmission.h.

◆ getJointOffset()

double transmission_interface::MiaMrlTransmission::getJointOffset ( ) const
inline

Definition at line 154 of file mia_mrl_transmission.h.

◆ h_mrl()

double transmission_interface::MiaMrlTransmission::h_mrl ( const double  pos)
inline

Mrl transmission first step function for pose: mu = mu = h_mrl(pos).

Parameters
pospose in the ros actuator-space (i.e. as returned by Mia hand [-255; +255]).
Returns
mu: pose in the mia actuator space.

Definition at line 42 of file mia_mrl_transmission.cpp.

◆ h_mrl_inv()

double transmission_interface::MiaMrlTransmission::h_mrl_inv ( const double  mu)

Mrl transmission first step inverse function for pose: pos = h_mrl_inv(mu).

Parameters
mupose in the mia actuator space.
Returns
pos: round pose in the ros actuator-space (i.e. as returned by Mia hand [-255; +255]).

Definition at line 51 of file mia_mrl_transmission.cpp.

◆ jointToActuatorEffort()

void transmission_interface::MiaMrlTransmission::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 at line 139 of file mia_mrl_transmission.cpp.

◆ jointToActuatorPosition()

void transmission_interface::MiaMrlTransmission::jointToActuatorPosition ( const transmission_interface::JointData &  jnt_data,
transmission_interface::ActuatorData &  act_data 
)

Transform position variables from joint to actuator space.

Parameters
jnt_datamrl joint target.
act_datareturned mrl actuator target.

Definition at line 117 of file mia_mrl_transmission.cpp.

◆ jointToActuatorVelocity()

void transmission_interface::MiaMrlTransmission::jointToActuatorVelocity ( const transmission_interface::JointData &  jnt_data,
transmission_interface::ActuatorData &  act_data 
)

Transform velocity variables from joint to actuator space.

Parameters
jnt_datamrl joint target.
act_datareturned mrl actuator target.

Definition at line 106 of file mia_mrl_transmission.cpp.

Member Data Documentation

◆ jnt_offset_

double transmission_interface::MiaMrlTransmission::jnt_offset_
private

Offset of teh joint.

Definition at line 158 of file mia_mrl_transmission.h.

◆ reduction_

double transmission_interface::MiaMrlTransmission::reduction_
private

Linear second step reduction of the tranmission.

Definition at line 157 of file mia_mrl_transmission.h.


The documentation for this class was generated from the following files: