Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
PanTiltInfo.hGo to the documentation of this file.00001 //-*-c++-*- 00002 #ifndef INCLUDED_PanTiltInfo_h 00003 #define INCLUDED_PanTiltInfo_h 00004 00005 #include <cmath> 00006 #include <stdlib.h> 00007 #include "CommonInfo.h" 00008 using namespace RobotInfo; 00009 00010 // see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags 00011 #if defined(TGT_PANTILT) 00012 # define TGT_IS_PANTILT 00013 # define TGT_HAS_CAMERA 1 00014 # define TGT_HAS_HEAD 1 00015 #endif 00016 00017 //! Declares configuration of a pan/tilt camera “robot”, such as number of joints, LEDs, etc. 00018 namespace PanTiltInfo { 00019 00020 // ******************************* 00021 // ROBOT CONFIGURATION 00022 // ******************************* 00023 00024 extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs 00025 00026 const unsigned int FrameTime=40; //!< time between frames in the motion system (milliseconds) 00027 const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) 00028 const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed 00029 00030 //!@name Output Types Information 00031 const unsigned NumWheels = 0; 00032 00033 const unsigned JointsPerArm = 0; 00034 const unsigned NumArms = 0; 00035 const unsigned NumArmJoints = JointsPerArm*NumArms; 00036 00037 const unsigned JointsPerLeg = 0; //!< The number of joints per leg 00038 const unsigned NumLegs = 0; //!< The number of legs 00039 const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs 00040 const unsigned NumHeadJoints = 2; //!< The number of joints in the pantilt 00041 const unsigned NumTailJoints = 0; //!< The number of joints assigned to the tail 00042 const unsigned NumMouthJoints = 0; //!< the number of joints that control the mouth 00043 const unsigned NumEarJoints = 0; //!< The number of joints which control the ears (NOT per ear, is total) 00044 const unsigned NumButtons = 0; //!< the number of buttons that are available 00045 const unsigned NumSensors = 0; //!< the number of sensors available 00046 const unsigned NumFacePanelLEDs = 0; //!< The number of face panel LEDs 00047 00048 const unsigned NumLEDs = 0; //!< The number of LEDs which can be controlled (one per dynamixel servo) 00049 const unsigned NumPIDJoints = NumWheels + NumArmJoints + NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints;; //!< servo pins 00050 00051 const unsigned NumOutputs = NumWheels + NumPIDJoints + NumLEDs; //!< the total number of outputs 00052 const unsigned NumReferenceFrames = NumOutputs + 1 + 1; //!< for the base and camera reference frames 00053 00054 using namespace Camera75DOF; 00055 //@} 00056 00057 00058 // ******************************* 00059 // OUTPUT OFFSETS 00060 // ******************************* 00061 00062 //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file 00063 //!@name Output Offsets 00064 00065 const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints 00066 const unsigned HeadOffset = PIDJointOffset; //!< The beginning of the head joints 00067 00068 const unsigned LEDOffset = PIDJointOffset + NumPIDJoints; //!< the offset of LEDs in WorldState::outputs and MotionCommand functions, see LedOffset_t for specific offsets 00069 00070 const unsigned BaseFrameOffset = NumOutputs; //!< Use with kinematics to refer to base reference frame 00071 const unsigned CameraFrameOffset = BaseFrameOffset+1; //!< Use with kinematics to refer to camera reference frame 00072 00073 //! The offsets of appendages with pan (heading), tilt (elevation), note that this should be added to HeadOffset, otherwise use HeadOffset_t (#HeadPanOffset and #HeadTiltOffset) 00074 enum TPROffset_t { 00075 PanOffset = 0, //!< pan/heading (horizontal) 00076 TiltOffset, //!< tilt/elevation (vertical) 00077 }; 00078 00079 //! These are 'absolute' offsets for the neck joints, don't need to add to HeadOffset like TPROffset_t values do 00080 enum HeadOffset_t { 00081 HeadPanOffset = HeadOffset, //!< pan/heading (horizontal) 00082 HeadTiltOffset, //!< tilt/elevation (vertical) 00083 }; 00084 00085 //@} 00086 00087 00088 // ******************************* 00089 // INPUT OFFSETS 00090 // ******************************* 00091 00092 00093 //! The order in which inputs should be stored 00094 //!@name Input Offsets 00095 00096 //! holds offsets to different buttons in WorldState::buttons[] 00097 /*! Should be a straight mapping to the ButtonSourceIDs 00098 * 00099 * Note that the chest (power) button is not a normal button. It kills 00100 * power to the motors at a hardware level, and isn't sensed in the 00101 * normal way. If you want to know when it is pressed (and you are 00102 * about to shut down) see PowerSrcID::PauseSID. 00103 * 00104 * @see WorldState::buttons @see ButtonSourceID_t 00105 * @hideinitializer */ 00106 enum ButtonOffset_t { }; 00107 00108 //! Provides a string name for each button 00109 const char* const buttonNames[NumButtons+1] = { NULL }; // non-empty array to avoid gcc 3.4.2 internal error 00110 00111 //! holds offset to different sensor values in WorldState::sensors[] 00112 /*! @see WorldState::sensors[] */ 00113 enum SensorOffset_t { }; 00114 00115 //! Provides a string name for each sensor 00116 const char* const sensorNames[NumSensors+1] = { NULL }; // non-empty array to avoid gcc 3.4.2 internal error 00117 00118 //@} 00119 00120 00121 //! Names for each of the outputs 00122 const char* const outputNames[NumReferenceFrames+1] = { 00123 "NECK:pan", 00124 "NECK:tilt", 00125 "BaseFrame", 00126 "CameraFrame", 00127 NULL 00128 }; 00129 00130 //! allocation declared in RobotInfo.cc 00131 extern const Capabilities capabilities; 00132 00133 //! Dynamixel servos don't use PID control. Instead, these values indicate compliance slope (P), punch (add to P*error), compliance margin (min error to start applying torque) (see ServoParam_t) 00134 /*! I believe the torque calculation goes something like: torque = (error<compliance) ? 0 : punch + P*error 00135 * Dynamixel servos allow different values to be supplied for CW vs. CCW motion, but we just use the same value for each */ 00136 const float DefaultPIDs[NumPIDJoints][3] = { 00137 {32,32,0}, {32,32,0} 00138 }; 00139 00140 //!These values are our recommended maximum joint velocities, in rad/ms 00141 /*! a value <= 0 means infinite speed (e.g. LEDs) 00142 * 00143 * These limits are <b>not</b> enforced by the framework. They are simply available for you to use as you see fit. 00144 * HeadPointerMC and PostureMC are primary examples of included classes which do respect these values (although they can be overridden) 00145 */ 00146 const float MaxOutputSpeed[NumOutputs] = { 00147 // servos 00148 0.8f,0.8f, 00149 }; 00150 00151 #ifndef RAD 00152 //!Just a little macro for converting degrees to radians 00153 #define RAD(deg) (((deg) * (float)M_PI ) / 180.0f) 00154 //!a flag so we undef these after we're done - do you have a cleaner solution? 00155 #define __RI_RAD_FLAG 00156 #endif 00157 00158 //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) 00159 const float outputRanges[NumOutputs][2] = { 00160 // servos 00161 {RAD(-150),RAD(150)}, {RAD(-92),RAD(75)}, 00162 }; 00163 00164 //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) 00165 const float mechanicalLimits[NumOutputs][2] = { 00166 // servos 00167 {RAD(-150),RAD(150)}, {RAD(-92),RAD(75)}, 00168 }; 00169 00170 #ifdef __RI_RAD_FLAG 00171 #undef RAD 00172 #undef __RI_RAD_FLAG 00173 #endif 00174 } 00175 00176 /*! @file 00177 * @brief Defines some capabilities of a simple pan-tilt camera “robot” 00178 * @author ejt (Creator) 00179 */ 00180 00181 #endif |
Tekkotsu v5.1CVS |
Generated Mon May 9 04:58:45 2016 by Doxygen 1.6.3 |