Go to the documentation of this file.
57 #ifndef WRIST_TRANSMISSION_H
58 #define WRIST_TRANSMISSION_H
68 class WristTransmission :
public Transmission
75 bool initXml(TiXmlElement *config);
87 std::vector<pr2_mechanism_model::JointState*>&);
89 std::vector<pr2_hardware_interface::Actuator*>&);
91 std::vector<pr2_hardware_interface::Actuator*>&);
93 std::vector<pr2_mechanism_model::JointState*>&);
94 void setReductions(std::vector<double>& ar, std::vector<double>& jr);
std::vector< double > joint_reduction_
bool initXml(TiXmlElement *config, Robot *robot)
Initializes the transmission from XML data.
void propagateEffortBackwards(std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &)
Uses the actuator's commanded effort to fill out the torque on the joint.
JointCalibrationSimulator joint_calibration_simulator_[2]
std::vector< double > actuator_reduction_
void setReductions(std::vector< double > &ar, std::vector< double > &jr)
void propagatePositionBackwards(std::vector< pr2_mechanism_model::JointState * > &, std::vector< pr2_hardware_interface::Actuator * > &)
Uses the joint position to fill out the actuator's encoder.
int simulated_actuator_timestamp_initialized_
void propagateEffort(std::vector< pr2_mechanism_model::JointState * > &, std::vector< pr2_hardware_interface::Actuator * > &)
Uses commanded joint efforts to fill out commanded motor currents.
void propagatePosition(std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &)
Uses encoder data to fill out joint position and velocities.
ros::Time simulated_actuator_start_time_
pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Mon Mar 6 2023 03:49:17