$search
#include <pr2_gripper_transmission.h>
Public Member Functions | |
bool | initXml (TiXmlElement *config) |
Initializes the transmission from XML data. | |
bool | initXml (TiXmlElement *config, Robot *robot) |
Initializes the transmission from XML data. | |
PR2GripperTransmission () | |
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 | 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. | |
void | propagatePosition (std::vector< pr2_hardware_interface::Actuator * > &, std::vector< pr2_mechanism_model::JointState * > &) |
Uses encoder data to fill out joint position and velocities. | |
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. | |
virtual | ~PR2GripperTransmission () |
Public Attributes | |
std::string | gap_joint_ |
double | gap_mechanical_reduction_ |
bool | has_simulated_passive_actuated_joint_ |
std::vector< std::string > | passive_joints_ |
double | simulated_reduction_ |
bool | use_simulated_actuated_joint_ |
Private Member Functions | |
void | computeGapStates (double MR, double MR_dot, double MT, double &theta, double &dtheta_dMR, double &dt_dtheta, double &dt_dMR, double &gap_size, double &gap_velocity, double &gap_effort) |
compute gap position, velocity and measured effort from actuator states | |
void | inverseGapStates (double gap_size, double &MR, double &dMR_dtheta, double &dtheta_dt, double &dMR_dt) |
void | inverseGapStates1 (double theta, double &MR, double &dMR_dtheta, double &dtheta_dt, double &dMR_dt) |
Private Attributes | |
double | a_ |
double | b_ |
double | gear_ratio_ |
double | h_ |
JointCalibrationSimulator | joint_calibration_simulator_ |
double | L0_ |
double | phi0_ |
double | r_ |
double | screw_reduction_ |
ros::Time | simulated_actuator_start_time_ |
int | simulated_actuator_timestamp_initialized_ |
double | t0_ |
double | theta0_ |
Definition at line 55 of file pr2_gripper_transmission.h.
pr2_mechanism_model::PR2GripperTransmission::PR2GripperTransmission | ( | ) | [inline] |
Definition at line 58 of file pr2_gripper_transmission.h.
virtual pr2_mechanism_model::PR2GripperTransmission::~PR2GripperTransmission | ( | ) | [inline, virtual] |
Definition at line 59 of file pr2_gripper_transmission.h.
void PR2GripperTransmission::computeGapStates | ( | double | MR, | |
double | MR_dot, | |||
double | MT, | |||
double & | theta, | |||
double & | dtheta_dMR, | |||
double & | dt_dtheta, | |||
double & | dt_dMR, | |||
double & | gap_size, | |||
double & | gap_velocity, | |||
double & | gap_effort | |||
) | [private] |
compute gap position, velocity and measured effort from actuator states
given actuator states (motor revolustion, joint torques), compute gap properties.
Definition at line 673 of file pr2_gripper_transmission.cpp.
bool PR2GripperTransmission::initXml | ( | TiXmlElement * | config | ) | [virtual] |
Initializes the transmission from XML data.
Reimplemented from pr2_mechanism_model::Transmission.
Definition at line 382 of file pr2_gripper_transmission.cpp.
bool pr2_mechanism_model::PR2GripperTransmission::initXml | ( | TiXmlElement * | config, | |
Robot * | robot | |||
) | [virtual] |
Initializes the transmission from XML data.
Implements pr2_mechanism_model::Transmission.
void PR2GripperTransmission::inverseGapStates | ( | double | gap_size, | |
double & | MR, | |||
double & | dMR_dtheta, | |||
double & | dtheta_dt, | |||
double & | dMR_dt | |||
) | [private] |
inverse of computeGapStates() need theta as input computes MR, dMR_dtheta, dtheta_dt, dMR_dt
Definition at line 730 of file pr2_gripper_transmission.cpp.
void PR2GripperTransmission::inverseGapStates1 | ( | double | theta, | |
double & | MR, | |||
double & | dMR_dtheta, | |||
double & | dtheta_dt, | |||
double & | dMR_dt | |||
) | [private] |
inverse of computeGapStates() need theta as input computes MR, dMR_dtheta, dtheta_dt, dMR_dt
Definition at line 746 of file pr2_gripper_transmission.cpp.
void pr2_mechanism_model::PR2GripperTransmission::propagateEffort | ( | std::vector< pr2_mechanism_model::JointState * > & | , | |
std::vector< pr2_hardware_interface::Actuator * > & | ||||
) | [virtual] |
Uses commanded joint efforts to fill out commanded motor currents.
Implements pr2_mechanism_model::Transmission.
void pr2_mechanism_model::PR2GripperTransmission::propagateEffortBackwards | ( | std::vector< pr2_hardware_interface::Actuator * > & | , | |
std::vector< pr2_mechanism_model::JointState * > & | ||||
) | [virtual] |
Uses the actuator's commanded effort to fill out the torque on the joint.
Implements pr2_mechanism_model::Transmission.
void pr2_mechanism_model::PR2GripperTransmission::propagatePosition | ( | std::vector< pr2_hardware_interface::Actuator * > & | , | |
std::vector< pr2_mechanism_model::JointState * > & | ||||
) | [virtual] |
Uses encoder data to fill out joint position and velocities.
Implements pr2_mechanism_model::Transmission.
void pr2_mechanism_model::PR2GripperTransmission::propagatePositionBackwards | ( | std::vector< pr2_mechanism_model::JointState * > & | , | |
std::vector< pr2_hardware_interface::Actuator * > & | ||||
) | [virtual] |
Uses the joint position to fill out the actuator's encoder.
Implements pr2_mechanism_model::Transmission.
double pr2_mechanism_model::PR2GripperTransmission::a_ [private] |
Definition at line 109 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::b_ [private] |
Definition at line 110 of file pr2_gripper_transmission.h.
Definition at line 72 of file pr2_gripper_transmission.h.
Definition at line 77 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::gear_ratio_ [private] |
Definition at line 103 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::h_ [private] |
Definition at line 108 of file pr2_gripper_transmission.h.
Definition at line 82 of file pr2_gripper_transmission.h.
JointCalibrationSimulator pr2_mechanism_model::PR2GripperTransmission::joint_calibration_simulator_ [private] |
Definition at line 119 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::L0_ [private] |
Definition at line 107 of file pr2_gripper_transmission.h.
std::vector<std::string> pr2_mechanism_model::PR2GripperTransmission::passive_joints_ |
Definition at line 89 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::phi0_ [private] |
Definition at line 105 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::r_ [private] |
Definition at line 111 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::screw_reduction_ [private] |
Definition at line 102 of file pr2_gripper_transmission.h.
Definition at line 117 of file pr2_gripper_transmission.h.
int pr2_mechanism_model::PR2GripperTransmission::simulated_actuator_timestamp_initialized_ [private] |
Definition at line 116 of file pr2_gripper_transmission.h.
Definition at line 80 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::t0_ [private] |
Definition at line 106 of file pr2_gripper_transmission.h.
double pr2_mechanism_model::PR2GripperTransmission::theta0_ [private] |
Definition at line 104 of file pr2_gripper_transmission.h.
Definition at line 81 of file pr2_gripper_transmission.h.