Implementation of the no-linear Mia Index Transmission.
More...
#include <mia_index_transmission.h>
|
| 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...
|
|
Implementation of the no-linear Mia Index Transmission.
Definition at line 34 of file mia_index_transmission.h.
◆ MiaIndexTransmission()
transmission_interface::MiaIndexTransmission::MiaIndexTransmission |
( |
| ) |
|
◆ actuatorToJointEffort()
void transmission_interface::MiaIndexTransmission::actuatorToJointEffort |
( |
const transmission_interface::ActuatorData & |
ind_act_state, |
|
|
transmission_interface::JointData & |
ind_jnt_data |
|
) |
| |
|
override |
◆ 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_state | index actuator actual state. |
ind_jnt_data | returned 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_state | index actuator actual state. |
ind_jnt_data | returned 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_a | velocity 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
-
spe | 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 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
-
spe | 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 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
-
alpha | position 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
-
delta | position 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
-
pos | pose 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
-
mu | pose 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_data | index joint target. |
ind_act_state | index actuator |
ind_act_cmd | returned 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 |
◆ 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_data | index joint target. |
ind_act_cmd | returned 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 |
◆ df_offset
std::vector<double> transmission_interface::MiaIndexTransmission::df_offset |
|
private |
◆ df_scale
std::vector<double> transmission_interface::MiaIndexTransmission::df_scale |
|
private |
◆ f_inv_offset
std::vector<double> transmission_interface::MiaIndexTransmission::f_inv_offset |
|
private |
◆ f_inv_scale
std::vector<double> transmission_interface::MiaIndexTransmission::f_inv_scale |
|
private |
◆ f_offset
std::vector<double> transmission_interface::MiaIndexTransmission::f_offset |
|
private |
◆ f_scale
std::vector<double> transmission_interface::MiaIndexTransmission::f_scale |
|
private |
◆ linear_reduction_
double transmission_interface::MiaIndexTransmission::linear_reduction_ |
|
private |
◆ x_intervals_df
std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_df |
|
private |
◆ x_intervals_f
std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_f |
|
private |
◆ x_intervals_f_inv
std::vector<double> transmission_interface::MiaIndexTransmission::x_intervals_f_inv |
|
private |
The documentation for this class was generated from the following files: