mia_hand_ros_control
rel 1.0.0
|
Go to the documentation of this file.
9 #ifndef MIA_INDEX_TRANSMISSION_H
10 #define MIA_INDEX_TRANSMISSION_H
19 #include <transmission_interface/transmission.h>
20 #include <transmission_interface/transmission_interface_exception.h>
43 const transmission_interface::ActuatorData& ind_act_state,
44 transmission_interface::JointData& ind_jnt_data)
override;
52 const transmission_interface::ActuatorData& ind_act_state,
53 transmission_interface::JointData& ind_jnt_data)
override;
61 const transmission_interface::ActuatorData& ind_act_state,
62 transmission_interface::JointData& ind_jnt_data)
override;
68 const transmission_interface::JointData& ind_jnt_data,
69 transmission_interface::ActuatorData& ind_act_cmd)
override;
77 const transmission_interface::JointData& ind_jnt_data,
78 transmission_interface::ActuatorData& ind_act_cmd)
override;
84 const transmission_interface::JointData& ind_jnt_data,
85 transmission_interface::ActuatorData& act_data)
override;
94 const transmission_interface::JointData& ind_jnt_data,
95 const transmission_interface::ActuatorData& ind_act_state,
96 transmission_interface::ActuatorData& ind_act_cmd) ;
103 double h_i(
const double pos);
110 double h_i_inv(
const double mu);
117 double dh_i(
const double spe);
124 double dh_i_inv(
const double omega_m);
131 double f(
const double alpha );
138 double f_inv(
const double delta );
145 double df(
const double omega_a );
148 std::size_t numActuators()
const {
return 1;}
149 std::size_t numJoints()
const {
return 1;}
215 #endif //MIA_INDEX_TRANSMISSION_H
std::vector< double > df_offset
Offset factors of the df funtion.
double f(const double alpha)
Index transmission second step function for position: delta = f(alpha)
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.
std::vector< double > f_inv_offset
Offset factors of the f_inv funtion.
double df(const double omega_a)
Index transmission second step function for velocity: alpha = f_inv(delta)
std::vector< double > x_intervals_f_inv
Upper limiits of the inputs intervals of the f_inv funtion.
std::vector< double > f_offset
Offset factors of the f funtion.
void actuatorToJointVelocity(const transmission_interface::ActuatorData &ind_act_state, transmission_interface::JointData &ind_jnt_data) override
Transform velocity variables from actuator to joint space.
Implementation of the no-linear Mia Index Transmission.
std::vector< double > df_scale
Scale factors of the df funtion.
void jointToActuatorVelocity(const transmission_interface::JointData &ind_jnt_data, transmission_interface::ActuatorData &act_data) override
unused
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.
std::vector< double > f_scale
Scales factors of the f funtion.
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.
double dh_i_inv(const double omega_m)
Index transmission first step inverse function for velocity: spe = dh_i_inv(omega_m)
void actuatorToJointPosition(const transmission_interface::ActuatorData &ind_act_state, transmission_interface::JointData &ind_jnt_data) override
Transform position variables from actuator to joint space.
std::vector< double > x_intervals_df
Upper limiits of the inputs intervals of the df funtion.
double dh_i(const double spe)
Index transmission first step function for velocity: omega_m = dh_i(spe).
double f_inv(const double delta)
Index transmission second step inverse function for position: alpha = f_inv(delta)
double h_i(const double pos)
Index transmission first step function for pose: mu = h_i(pos).
std::vector< double > x_intervals_f
Upper limiits of the inputs intervals of the f funtion.
std::vector< double > f_inv_scale
Scale factors of the f_inv funtion.
double h_i_inv(const double mu)
Index transmission first step inverse function for pose: pos = h_i_inv(mu)
void jointToActuatorPosition(const transmission_interface::JointData &ind_jnt_data, transmission_interface::ActuatorData &ind_act_cmd) override
Transform position variables from joint to actuator space.
MiaIndexTransmission()
Class constructor.