00001 00029 #ifndef _JOINT_0_TRANSMISSION_HPP_ 00030 #define _JOINT_0_TRANSMISSION_HPP_ 00031 00032 #include <tinyxml.h> 00033 #include "pr2_mechanism_model/transmission.h" 00034 #include "pr2_mechanism_model/joint.h" 00035 #include "pr2_hardware_interface/hardware_interface.h" 00036 #include "pr2_mechanism_model/joint_calibration_simulator.h" 00037 00038 namespace sr_mechanism_model 00039 { 00040 class J0Transmission : public pr2_mechanism_model::Transmission 00041 { 00042 public: 00043 J0Transmission() {} 00044 ~J0Transmission() {} 00045 00046 bool initXml(TiXmlElement *config, pr2_mechanism_model::Robot *robot); 00047 bool initXml(TiXmlElement *config); 00048 00049 double mechanical_reduction_; 00050 00051 void propagatePosition(std::vector<pr2_hardware_interface::Actuator*>&, 00052 std::vector<pr2_mechanism_model::JointState*>&); 00053 void propagatePositionBackwards(std::vector<pr2_mechanism_model::JointState*>&, 00054 std::vector<pr2_hardware_interface::Actuator*>&); 00055 void propagateEffort(std::vector<pr2_mechanism_model::JointState*>&, 00056 std::vector<pr2_hardware_interface::Actuator*>&); 00057 void propagateEffortBackwards(std::vector<pr2_hardware_interface::Actuator*>&, 00058 std::vector<pr2_mechanism_model::JointState*>&); 00059 00060 private: 00061 int simulated_actuator_timestamp_initialized_; 00062 ros::Time simulated_actuator_start_time_; 00063 00064 pr2_mechanism_model::JointCalibrationSimulator joint_calibration_simulator_; 00065 00066 bool init_joint(TiXmlElement *jel, pr2_mechanism_model::Robot *robot); 00067 }; 00068 00069 } //end namespace sr_mechanism_model 00070 00071 /* For the emacs weenies in the crowd. 00072 Local Variables: 00073 c-basic-offset: 2 00074 End: 00075 */ 00076 00077 #endif