wrist_transmission.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 /*
00035  * Author: Melonee Wise
00036 
00037    example xml:
00038     <robot name="wrist_trans">
00039       <joint name="right_wrist_flex_joint" type="revolute">
00040         <limit min="-0.157" max="2.409" effort="5" velocity="5" />
00041         <axis xyz="0 0 1" />
00042       </joint>
00043 
00044       <joint name="right_wrist_roll_joint" type="continuous">
00045         <limit min="0.0" max="0.0" effort="5" velocity="5" />
00046         <axis xyz="0 0 1" />
00047       </joint>
00048 
00049       <transmission type="WristTransmission" name="wrist_trans">
00050         <rightActuator name="right_wrist_r_motor"  mechanicalReduction="60.17"/>
00051         <leftActuator name="right_wrist_l_motor" mechanicalReduction="60.17"/>
00052         <flexJoint name="wrist_right_flex_joint" mechanicalReduction="1"/>
00053         <rollJoint name="wrist_right_roll_joint" mechanicalReduction="1"/>
00054       </transmission>
00055     </robot>
00056  */
00057 #ifndef WRIST_TRANSMISSION_H
00058 #define WRIST_TRANSMISSION_H
00059 
00060 #include <tinyxml.h>
00061 #include "pr2_mechanism_model/transmission.h"
00062 #include "pr2_mechanism_model/joint.h"
00063 #include "pr2_hardware_interface/hardware_interface.h"
00064 #include "pr2_mechanism_model/joint_calibration_simulator.h"
00065 
00066 namespace pr2_mechanism_model {
00067 
00068 class WristTransmission : public Transmission
00069 {
00070 public:
00071   WristTransmission();
00072   ~WristTransmission() {}
00073 
00074   bool initXml(TiXmlElement *config, Robot *robot);
00075   bool initXml(TiXmlElement *config);
00076 
00077   std::vector<double> actuator_reduction_;
00078   std::vector<double> joint_reduction_;
00079   double joint_offset_[2];
00080 
00081   // Describes the order of the actuators and the joints in the arrays
00082   // of names and of those passed to propagate*
00083   enum { RIGHT_MOTOR, LEFT_MOTOR };
00084   enum { FLEX_JOINT, ROLL_JOINT };
00085 
00086   void propagatePosition(std::vector<pr2_hardware_interface::Actuator*>&,
00087                          std::vector<pr2_mechanism_model::JointState*>&);
00088   void propagatePositionBackwards(std::vector<pr2_mechanism_model::JointState*>&,
00089                                   std::vector<pr2_hardware_interface::Actuator*>&);
00090   void propagateEffort(std::vector<pr2_mechanism_model::JointState*>&,
00091                        std::vector<pr2_hardware_interface::Actuator*>&);
00092   void propagateEffortBackwards(std::vector<pr2_hardware_interface::Actuator*>&,
00093                                 std::vector<pr2_mechanism_model::JointState*>&);
00094   void setReductions(std::vector<double>& ar, std::vector<double>& jr);
00095 
00096 private:
00097   int simulated_actuator_timestamp_initialized_;
00098   ros::Time simulated_actuator_start_time_;
00099 
00100   JointCalibrationSimulator joint_calibration_simulator_[2];
00101 };
00102 
00103 } // namespace pr2_mechanism_model
00104 
00105 #endif


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Thu Dec 12 2013 12:03:56