Public Member Functions | Private Attributes | List of all members
pr2_mechanism_model::PR2BeltCompensatorTransmission Class Reference

#include <pr2_belt_transmission.h>

Inheritance diagram for pr2_mechanism_model::PR2BeltCompensatorTransmission:
Inheritance graph
[legend]

Public Member Functions

bool initXml (TiXmlElement *config, Robot *robot)
 Initializes the transmission from XML data. More...
 
bool initXml (TiXmlElement *config)
 Initializes the transmission from XML data. More...
 
 PR2BeltCompensatorTransmission ()
 
void propagateEffort (std::vector< pr2_mechanism_model::JointState *> &, std::vector< pr2_hardware_interface::Actuator *> &)
 Uses commanded joint efforts to fill out commanded motor currents. More...
 
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. More...
 
void propagatePosition (std::vector< pr2_hardware_interface::Actuator *> &, std::vector< pr2_mechanism_model::JointState *> &)
 Uses encoder data to fill out joint position and velocities. More...
 
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. More...
 
 ~PR2BeltCompensatorTransmission ()
 
- Public Member Functions inherited from pr2_mechanism_model::Transmission
 Transmission ()
 Constructor. More...
 
virtual ~Transmission ()
 Destructor. More...
 

Private Attributes

double delta_motor_vel_
 
double dt
 
double halfdt_backwards_
 
JointCalibrationSimulator joint_calibration_simulator_
 
double Kd_motor_
 
double lambda_combo_
 
double lambda_joint_
 
double lambda_motor_
 
double last_defl_acc_
 
double last_defl_pos_
 
double last_defl_vel_
 
double last_jnt1_acc_
 
double last_jnt1_pos_
 
double last_jnt1_vel_
 
double last_joint_pos_
 
double last_joint_pos_backwards_
 
double last_joint_vel_
 
double last_joint_vel_backwards_
 
double last_motor_acc_backwards_
 
double last_motor_damping_force_
 
double last_motor_pos_
 
double last_motor_pos_backwards_
 
double last_motor_vel_
 
double last_motor_vel_backwards_
 
ros::Duration last_timestamp_
 
ros::Duration last_timestamp_backwards_
 
double mechanical_reduction_
 
double motor_force_backwards_
 
ros::Time simulated_actuator_start_time_
 
int simulated_actuator_timestamp_initialized_
 
double trans_compl_
 
double trans_tau_
 

Additional Inherited Members

- Public Attributes inherited from pr2_mechanism_model::Transmission
std::vector< std::string > actuator_names_
 
std::vector< std::string > joint_names_
 
std::string name_
 the name of the transmission More...
 

Detailed Description

PROPAGATE*BACKWARDS IS NOT GUARANTEED TO WORK

Definition at line 47 of file pr2_belt_transmission.h.

Constructor & Destructor Documentation

◆ PR2BeltCompensatorTransmission()

pr2_mechanism_model::PR2BeltCompensatorTransmission::PR2BeltCompensatorTransmission ( )
inline

Definition at line 50 of file pr2_belt_transmission.h.

◆ ~PR2BeltCompensatorTransmission()

pr2_mechanism_model::PR2BeltCompensatorTransmission::~PR2BeltCompensatorTransmission ( )
inline

Definition at line 51 of file pr2_belt_transmission.h.

Member Function Documentation

◆ initXml() [1/2]

bool pr2_mechanism_model::PR2BeltCompensatorTransmission::initXml ( TiXmlElement *  config,
Robot robot 
)
virtual

Initializes the transmission from XML data.

Implements pr2_mechanism_model::Transmission.

◆ initXml() [2/2]

bool pr2_mechanism_model::PR2BeltCompensatorTransmission::initXml ( TiXmlElement *  config)
virtual

Initializes the transmission from XML data.

Reimplemented from pr2_mechanism_model::Transmission.

◆ propagateEffort()

void pr2_mechanism_model::PR2BeltCompensatorTransmission::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.

◆ propagateEffortBackwards()

void pr2_mechanism_model::PR2BeltCompensatorTransmission::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.

◆ propagatePosition()

void pr2_mechanism_model::PR2BeltCompensatorTransmission::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.

◆ propagatePositionBackwards()

void pr2_mechanism_model::PR2BeltCompensatorTransmission::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.

Member Data Documentation

◆ delta_motor_vel_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::delta_motor_vel_
private

Definition at line 92 of file pr2_belt_transmission.h.

◆ dt

double pr2_mechanism_model::PR2BeltCompensatorTransmission::dt
private

Definition at line 67 of file pr2_belt_transmission.h.

◆ halfdt_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::halfdt_backwards_
private

Definition at line 98 of file pr2_belt_transmission.h.

◆ joint_calibration_simulator_

JointCalibrationSimulator pr2_mechanism_model::PR2BeltCompensatorTransmission::joint_calibration_simulator_
private

Definition at line 113 of file pr2_belt_transmission.h.

◆ Kd_motor_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::Kd_motor_
private

Definition at line 73 of file pr2_belt_transmission.h.

◆ lambda_combo_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::lambda_combo_
private

Definition at line 76 of file pr2_belt_transmission.h.

◆ lambda_joint_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::lambda_joint_
private

Definition at line 75 of file pr2_belt_transmission.h.

◆ lambda_motor_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::lambda_motor_
private

Definition at line 74 of file pr2_belt_transmission.h.

◆ last_defl_acc_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_defl_acc_
private

Definition at line 87 of file pr2_belt_transmission.h.

◆ last_defl_pos_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_defl_pos_
private

Definition at line 85 of file pr2_belt_transmission.h.

◆ last_defl_vel_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_defl_vel_
private

Definition at line 86 of file pr2_belt_transmission.h.

◆ last_jnt1_acc_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_jnt1_acc_
private

Definition at line 83 of file pr2_belt_transmission.h.

◆ last_jnt1_pos_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_jnt1_pos_
private

Definition at line 81 of file pr2_belt_transmission.h.

◆ last_jnt1_vel_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_jnt1_vel_
private

Definition at line 82 of file pr2_belt_transmission.h.

◆ last_joint_pos_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_joint_pos_
private

Definition at line 89 of file pr2_belt_transmission.h.

◆ last_joint_pos_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_joint_pos_backwards_
private

Definition at line 106 of file pr2_belt_transmission.h.

◆ last_joint_vel_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_joint_vel_
private

Definition at line 90 of file pr2_belt_transmission.h.

◆ last_joint_vel_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_joint_vel_backwards_
private

Definition at line 107 of file pr2_belt_transmission.h.

◆ last_motor_acc_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_acc_backwards_
private

Definition at line 104 of file pr2_belt_transmission.h.

◆ last_motor_damping_force_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_damping_force_
private

Definition at line 93 of file pr2_belt_transmission.h.

◆ last_motor_pos_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_pos_
private

Definition at line 78 of file pr2_belt_transmission.h.

◆ last_motor_pos_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_pos_backwards_
private

Definition at line 102 of file pr2_belt_transmission.h.

◆ last_motor_vel_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_vel_
private

Definition at line 79 of file pr2_belt_transmission.h.

◆ last_motor_vel_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::last_motor_vel_backwards_
private

Definition at line 103 of file pr2_belt_transmission.h.

◆ last_timestamp_

ros::Duration pr2_mechanism_model::PR2BeltCompensatorTransmission::last_timestamp_
private

Definition at line 66 of file pr2_belt_transmission.h.

◆ last_timestamp_backwards_

ros::Duration pr2_mechanism_model::PR2BeltCompensatorTransmission::last_timestamp_backwards_
private

Definition at line 97 of file pr2_belt_transmission.h.

◆ mechanical_reduction_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::mechanical_reduction_
private

Definition at line 70 of file pr2_belt_transmission.h.

◆ motor_force_backwards_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::motor_force_backwards_
private

Definition at line 100 of file pr2_belt_transmission.h.

◆ simulated_actuator_start_time_

ros::Time pr2_mechanism_model::PR2BeltCompensatorTransmission::simulated_actuator_start_time_
private

Definition at line 110 of file pr2_belt_transmission.h.

◆ simulated_actuator_timestamp_initialized_

int pr2_mechanism_model::PR2BeltCompensatorTransmission::simulated_actuator_timestamp_initialized_
private

Definition at line 109 of file pr2_belt_transmission.h.

◆ trans_compl_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::trans_compl_
private

Definition at line 71 of file pr2_belt_transmission.h.

◆ trans_tau_

double pr2_mechanism_model::PR2BeltCompensatorTransmission::trans_tau_
private

Definition at line 72 of file pr2_belt_transmission.h.


The documentation for this class was generated from the following file:


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Tue Mar 7 2023 03:54:53