pr2_mechanism_model::PR2GripperTransmission Class Reference

#include <pr2_gripper_transmission.h>

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

List of all members.

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_
std::vector< std::string > passive_joints_

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 getRateFromMaxRateJoint (std::vector< pr2_mechanism_model::JointState * > &js, std::vector< pr2_hardware_interface::Actuator * > &as, int &maxRateJointIndex, double &rate)
void inverseGapStates (double theta, double &MR, double &dMR_dtheta, double &dtheta_dt, double &dMR_dt)

Private Attributes

double a_
double b_
int default_passive_joint_index_from_sim
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_
bool use_simulated_gripper_joint
 new option to turn off using passive joints for torque control, position detection in sim

Detailed Description

Definition at line 55 of file pr2_gripper_transmission.h.


Constructor & Destructor Documentation

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.


Member Function Documentation

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 488 of file pr2_gripper_transmission.cpp.

void pr2_mechanism_model::PR2GripperTransmission::getRateFromMaxRateJoint ( std::vector< pr2_mechanism_model::JointState * > &  js,
std::vector< pr2_hardware_interface::Actuator * > &  as,
int &  maxRateJointIndex,
double &  rate 
) [private]
bool PR2GripperTransmission::initXml ( TiXmlElement *  config  )  [virtual]

Initializes the transmission from XML data.

Reimplemented from pr2_mechanism_model::Transmission.

Definition at line 331 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  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 545 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.


Member Data Documentation

Definition at line 113 of file pr2_gripper_transmission.h.

Definition at line 114 of file pr2_gripper_transmission.h.

Definition at line 100 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.

Definition at line 107 of file pr2_gripper_transmission.h.

Definition at line 112 of file pr2_gripper_transmission.h.

Definition at line 123 of file pr2_gripper_transmission.h.

Definition at line 111 of file pr2_gripper_transmission.h.

Definition at line 84 of file pr2_gripper_transmission.h.

Definition at line 109 of file pr2_gripper_transmission.h.

Definition at line 115 of file pr2_gripper_transmission.h.

Definition at line 106 of file pr2_gripper_transmission.h.

Definition at line 121 of file pr2_gripper_transmission.h.

Definition at line 120 of file pr2_gripper_transmission.h.

Definition at line 110 of file pr2_gripper_transmission.h.

Definition at line 108 of file pr2_gripper_transmission.h.

new option to turn off using passive joints for torque control, position detection in sim

Definition at line 88 of file pr2_gripper_transmission.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Enumerator Defines


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Fri Jan 11 09:32:54 2013