30 #ifndef TRANSMISSION_INTERFACE_DIFFERENTIAL_TRANSMISSION_H 31 #define TRANSMISSION_INTERFACE_DIFFERENTIAL_TRANSMISSION_H 127 const std::vector<double>& joint_reduction,
128 const std::vector<double>& joint_offset = std::vector<double>(2, 0.0));
204 const std::vector<double>& joint_reduction,
205 const std::vector<double>& joint_offset)
237 *jnt_data.
effort[0] = jr[0] * (*act_data.
effort[0] * ar[0] + *act_data.
effort[1] * ar[1]);
238 *jnt_data.
effort[1] = jr[1] * (*act_data.
effort[0] * ar[0] - *act_data.
effort[1] * ar[1]);
276 *act_data.
effort[0] = (*jnt_data.
effort[0] / jr[0] + *jnt_data.
effort[1] / jr[1]) / (2.0 * ar[0]);
277 *act_data.
effort[1] = (*jnt_data.
effort[0] / jr[0] - *jnt_data.
effort[1] / jr[1]) / (2.0 * ar[1]);
304 *act_data.
position[0] = (jnt_pos_off[0] * jr[0] + jnt_pos_off[1] * jr[1]) * ar[0];
305 *act_data.
position[1] = (jnt_pos_off[0] * jr[0] - jnt_pos_off[1] * jr[1]) * ar[1];
310 #endif // TRANSMISSION_INTERFACE_DIFFERENTIAL_TRANSMISSION_H void jointToActuatorVelocity(const JointData &jnt_data, ActuatorData &act_data)
Transform velocity variables from joint to actuator space.
std::vector< double * > velocity
std::size_t numActuators() const
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
std::vector< double * > position
void jointToActuatorEffort(const JointData &jnt_data, ActuatorData &act_data)
Transform effort variables from joint to actuator space.
const std::vector< double > & getActuatorReduction() const
const std::vector< double > & getJointReduction() const
std::vector< double > jnt_offset_
const std::vector< double > & getJointOffset() const
DifferentialTransmission(const std::vector< double > &actuator_reduction, const std::vector< double > &joint_reduction, const std::vector< double > &joint_offset=std::vector< double >(2, 0.0))
void actuatorToJointPosition(const ActuatorData &act_data, JointData &jnt_data)
Transform position variables from actuator to joint space.
std::size_t numJoints() const
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
std::vector< double * > velocity
void actuatorToJointVelocity(const ActuatorData &act_data, JointData &jnt_data)
Transform velocity variables from actuator to joint space.
void jointToActuatorPosition(const JointData &jnt_data, ActuatorData &act_data)
Transform position variables from joint to actuator space.
std::vector< double * > position
void actuatorToJointEffort(const ActuatorData &act_data, JointData &jnt_data)
Transform effort variables from actuator to joint space.
std::vector< double * > effort
std::vector< double * > effort
Abstract base class for representing mechanical transmissions.
Implementation of a differential transmission.
std::vector< double > act_reduction_
std::vector< double > jnt_reduction_