30 #ifndef PR2_BELT_COMPENSATOR_TRANSMISSION_H 31 #define PR2_BELT_COMPENSATOR_TRANSMISSION_H 54 bool initXml(TiXmlElement *config);
57 std::vector<pr2_mechanism_model::JointState*>&);
59 std::vector<pr2_hardware_interface::Actuator*>&);
61 std::vector<pr2_hardware_interface::Actuator*>&);
63 std::vector<pr2_mechanism_model::JointState*>&);
~PR2BeltCompensatorTransmission()
ros::Time simulated_actuator_start_time_
void propagatePosition(std::vector< pr2_hardware_interface::Actuator *> &, std::vector< pr2_mechanism_model::JointState *> &)
Uses encoder data to fill out joint position and velocities.
double mechanical_reduction_
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.
void propagateEffort(std::vector< pr2_mechanism_model::JointState *> &, std::vector< pr2_hardware_interface::Actuator *> &)
Uses commanded joint efforts to fill out commanded motor currents.
ros::Duration last_timestamp_backwards_
bool initXml(TiXmlElement *config, Robot *robot)
Initializes the transmission from XML data.
int simulated_actuator_timestamp_initialized_
double last_joint_pos_backwards_
double last_motor_vel_backwards_
double last_motor_damping_force_
ros::Duration last_timestamp_
PR2BeltCompensatorTransmission()
double last_motor_pos_backwards_
JointCalibrationSimulator joint_calibration_simulator_
double last_motor_acc_backwards_
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.
This class provides the controllers with an interface to the robot model.
double motor_force_backwards_
double last_joint_vel_backwards_