mia_hand_ros_control  rel 1.0.0
transmission_interface::MiaIndexTransmission Class Reference

Implementation of the no-linear Mia Index Transmission. More...

#include <mia_index_transmission.h>

Inheritance diagram for transmission_interface::MiaIndexTransmission:
Collaboration diagram for transmission_interface::MiaIndexTransmission:

Public Member Functions

 MiaIndexTransmission ()
 Class constructor. More...
 
void actuatorToJointEffort (const transmission_interface::ActuatorData &ind_act_state, transmission_interface::JointData &ind_jnt_data) override
 Do not use this methos since Mia hand has not effort control. More...
 
void actuatorToJointPosition (const transmission_interface::ActuatorData &ind_act_state, transmission_interface::JointData &ind_jnt_data) override
 Transform position variables from actuator to joint space. More...
 
void actuatorToJointVelocity (const transmission_interface::ActuatorData &ind_act_state, transmission_interface::JointData &ind_jnt_data) override
 Transform velocity variables from actuator to joint space. More...
 
void jointToActuatorEffort (const transmission_interface::JointData &ind_jnt_data, transmission_interface::ActuatorData &ind_act_cmd) override
 Do not use this methos since Mia hand has not effort control. More...
 
void jointToActuatorPosition (const transmission_interface::JointData &ind_jnt_data, transmission_interface::ActuatorData &ind_act_cmd) override
 Transform position variables from joint to actuator space. More...
 
void jointToActuatorVelocity (const transmission_interface::JointData &ind_jnt_data, transmission_interface::ActuatorData &act_data) override
 unused More...
 
void IndexjointToActuatorVelocity (const transmission_interface::JointData &ind_jnt_data, const transmission_interface::ActuatorData &ind_act_state, transmission_interface::ActuatorData &ind_act_cmd)
 Transform velocity variables from joint to actuator space. More...
 
double h_i (const double pos)
 Index transmission first step function for pose: mu = h_i(pos). More...
 
double h_i_inv (const double mu)
 Index transmission first step inverse function for pose: pos = h_i_inv(mu) More...
 
double dh_i (const double spe)
 Index transmission first step function for velocity: omega_m = dh_i(spe). More...
 
double dh_i_inv (const double omega_m)
 Index transmission first step inverse function for velocity: spe = dh_i_inv(omega_m) More...
 
double f (const double alpha)
 Index transmission second step function for position: delta = f(alpha) More...
 
double f_inv (const double delta)
 Index transmission second step inverse function for position: alpha = f_inv(delta) More...
 
double df (const double omega_a)
 Index transmission second step function for velocity: alpha = f_inv(delta) More...
 

Private Attributes

double linear_reduction_
 
std::vector< double > x_intervals_f
 Upper limiits of the inputs intervals of the f funtion. More...
 
std::vector< double > x_intervals_f_inv
 Upper limiits of the inputs intervals of the f_inv funtion. More...
 
std::vector< double > x_intervals_df
 Upper limiits of the inputs intervals of the df funtion. More...
 
std::vector< double > f_scale
 Scales factors of the f funtion. More...
 
std::vector< double > f_offset
 Offset factors of the f funtion. More...
 
std::vector< double > f_inv_scale
 Scale factors of the f_inv funtion. More...
 
std::vector< double > f_inv_offset
 Offset factors of the f_inv funtion. More...
 
std::vector< double > df_scale
 Scale factors of the df funtion. More...
 
std::vector< double > df_offset
 Offset factors of the df funtion. More...
 

Detailed Description

Implementation of the no-linear Mia Index Transmission.

Definition at line 34 of file mia_index_transmission.h.

Constructor & Destructor Documentation

◆ MiaIndexTransmission()

transmission_interface::MiaIndexTransmission::MiaIndexTransmission ( )

Class constructor.

Definition at line 21 of file mia_index_transmission.cpp.

Member Function Documentation

◆ actuatorToJointEffort()

void transmission_interface::MiaIndexTransmission::actuatorToJointEffort ( const transmission_interface::ActuatorData &  ind_act_state,
transmission_interface::JointData &  ind_jnt_data 
)
override

Do not use this methos since Mia hand has not effort control.

Definition at line 334 of file mia_index_transmission.cpp.

◆ actuatorToJointPosition()

void transmission_interface::MiaIndexTransmission::actuatorToJointPosition ( const transmission_interface::ActuatorData &  ind_act_state,
transmission_interface::JointData &  ind_jnt_data 
)
override

Transform position variables from actuator to joint space.

Parameters
ind_act_stateindex actuator actual state.
ind_jnt_datareturned index joint state.

Definition at line 240 of file mia_index_transmission.cpp.

◆ actuatorToJointVelocity()

void transmission_interface::MiaIndexTransmission::actuatorToJointVelocity ( const transmission_interface::ActuatorData &  ind_act_state,
transmission_interface::JointData &  ind_jnt_data 
)
override

Transform velocity variables from actuator to joint space.

Parameters
ind_act_stateindex actuator actual state.
ind_jnt_datareturned index joint joint.

Definition at line 256 of file mia_index_transmission.cpp.

◆ df()

double transmission_interface::MiaIndexTransmission::df ( const double  omega_a)

Index transmission second step function for velocity: alpha = f_inv(delta)

Parameters
omega_avelocity f the intermediate step of the transmission.
Returns
omega_d: velocity in the mia joint space.

Definition at line 185 of file mia_index_transmission.cpp.

◆ dh_i()

double transmission_interface::MiaIndexTransmission::dh_i ( const double  spe)

Index transmission first step function for velocity: omega_m = dh_i(spe).

Parameters
spevelocity 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 81 of file mia_index_transmission.cpp.

◆ dh_i_inv()

double transmission_interface::MiaIndexTransmission::dh_i_inv ( const double  omega_m)

Index transmission first step inverse function for velocity: spe = dh_i_inv(omega_m)

Parameters
spevelocity 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 90 of file mia_index_transmission.cpp.

◆ f()

double transmission_interface::MiaIndexTransmission::f ( const double  alpha)

Index transmission second step function for position: delta = f(alpha)

Parameters
alphaposition of the intermediate step of the transmission.
Returns
delta: position in the mia joint space.

Definition at line 100 of file mia_index_transmission.cpp.

◆ f_inv()

double transmission_interface::MiaIndexTransmission::f_inv ( const double  delta)

Index transmission second step inverse function for position: alpha = f_inv(delta)

Parameters
deltaposition in the mia joint space.
Returns
delta: alpha: position of the intermediate step of the transmission.

Definition at line 143 of file mia_index_transmission.cpp.

◆ h_i()

double transmission_interface::MiaIndexTransmission::h_i ( const double  pos)

Index transmission first step function for pose: mu = h_i(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 63 of file mia_index_transmission.cpp.

◆ h_i_inv()

double transmission_interface::MiaIndexTransmission::h_i_inv ( const double  mu)

Index transmission first step inverse function for pose: pos = h_i_inv(mu)

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

Definition at line 72 of file mia_index_transmission.cpp.

◆ IndexjointToActuatorVelocity()

void transmission_interface::MiaIndexTransmission::IndexjointToActuatorVelocity ( const transmission_interface::JointData &  ind_jnt_data,
const transmission_interface::ActuatorData &  ind_act_state,
transmission_interface::ActuatorData &  ind_act_cmd 
)

Transform velocity variables from joint to actuator space.

Parameters
ind_jnt_dataindex joint target.
ind_act_stateindex actuator
ind_act_cmdreturned actuator joint target.

Definition at line 297 of file mia_index_transmission.cpp.

◆ jointToActuatorEffort()

void transmission_interface::MiaIndexTransmission::jointToActuatorEffort ( const transmission_interface::JointData &  ind_jnt_data,
transmission_interface::ActuatorData &  ind_act_cmd 
)
override

Do not use this methos since Mia hand has not effort control.

Definition at line 346 of file mia_index_transmission.cpp.

◆ jointToActuatorPosition()

void transmission_interface::MiaIndexTransmission::jointToActuatorPosition ( const transmission_interface::JointData &  ind_jnt_data,
transmission_interface::ActuatorData &  ind_act_cmd 
)
override

Transform position variables from joint to actuator space.

Parameters
ind_jnt_dataindex joint target.
ind_act_cmdreturned index actuator target.

Definition at line 280 of file mia_index_transmission.cpp.

◆ jointToActuatorVelocity()

void transmission_interface::MiaIndexTransmission::jointToActuatorVelocity ( const transmission_interface::JointData &  ind_jnt_data,
transmission_interface::ActuatorData &  act_data 
)
override

unused

Definition at line 321 of file mia_index_transmission.cpp.

Member Data Documentation

◆ df_offset

std::vector<double> transmission_interface::MiaIndexTransmission::df_offset
private

Offset factors of the df funtion.

See also
df().

Definition at line 216 of file mia_index_transmission.h.

◆ df_scale

std::vector<double> transmission_interface::MiaIndexTransmission::df_scale
private

Scale factors of the df funtion.

See also
df().

Definition at line 210 of file mia_index_transmission.h.

◆ f_inv_offset

std::vector<double> transmission_interface::MiaIndexTransmission::f_inv_offset
private

Offset factors of the f_inv funtion.

See also
f_inv().

Definition at line 204 of file mia_index_transmission.h.

◆ f_inv_scale

std::vector<double> transmission_interface::MiaIndexTransmission::f_inv_scale
private

Scale factors of the f_inv funtion.

See also
f_inv().

Definition at line 198 of file mia_index_transmission.h.

◆ f_offset

std::vector<double> transmission_interface::MiaIndexTransmission::f_offset
private

Offset factors of the f funtion.

See also
f().

Definition at line 192 of file mia_index_transmission.h.

◆ f_scale

std::vector<double> transmission_interface::MiaIndexTransmission::f_scale
private

Scales factors of the f funtion.

See also
f().

Definition at line 186 of file mia_index_transmission.h.

◆ linear_reduction_

double transmission_interface::MiaIndexTransmission::linear_reduction_
private

Definition at line 162 of file mia_index_transmission.h.

◆ x_intervals_df

std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_df
private

Upper limiits of the inputs intervals of the df funtion.

See also
df().

Definition at line 180 of file mia_index_transmission.h.

◆ x_intervals_f

std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_f
private

Upper limiits of the inputs intervals of the f funtion.

See also
f().

Definition at line 168 of file mia_index_transmission.h.

◆ x_intervals_f_inv

std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_f_inv
private

Upper limiits of the inputs intervals of the f_inv funtion.

See also
f_inv().

Definition at line 174 of file mia_index_transmission.h.


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