CDxlConfig.h
Go to the documentation of this file.
00001 // Dynamixel control code - header file
00002 // Copyright (c) 2008 Erik Schuitema, Eelko van Breda
00003 // Delft University of Technology
00004 // www.dbl.tudelft.nl
00005 
00006 #ifndef __DYNAMIXELCONFIG_H_INCLUDED__
00007 #define __DYNAMIXELCONFIG_H_INCLUDED__
00008 
00009 #include "CDxlGeneric.h"
00010 #include "dynamixel/DynamixelSpecs.h"
00011 #include "CDxlGroup.h"
00012 
00013 
00014 #include <threemxl/platform/io/configuration/Configuration.h>
00015 #include <threemxl/platform/io/configuration/OptionVars.h>
00016 
00017 #define DXLCONFIG_NUM_CALIBPOINTS       301
00018 
00019 // Conversion factors between Dynamixel and SI units
00020 #define DXL_NUM_POSITIONS                               DXL_RX28_NUM_POSITIONS
00021 #define DXL_MAX_POSITION                                DXL_RX28_MAX_POSITION
00022 #define DXL_SPEED_TO_RAD_S                              DXL_RX28_SPEED_TO_RAD_S
00023 #define DXL_STEPS_TO_RAD                                DXL_RX28_STEPS_TO_RAD
00024 #define DXL_TORQUE_TO_RATIO                             DXL_RX28_TORQUE_TO_RATIO
00025 
00026 // Temperature needs no conversion
00027 #define DXL_MAX_RAD_S_SPEED                             (DXL_MAX_POSITION*DXL_SPEED_TO_RAD_S)
00028 #define DXL_MAX_RAD_ANGLE                               (DXL_MAX_POSITION*DXL_STEPS_TO_RAD)
00029 
00030 #define MOTOR_CONSTANT_MULTIPLIER 10000
00031 
00032 enum EDxlCalibType
00033 {
00034         dxlCtNone,
00035         dxlCtAuto,      // Calib data obtained with the automatic calibration device
00036         dxlCtManual     // Calib data obtained with the manual calibration device ('wijzerplaat')
00037 };
00038 
00039 // Forward declaration
00040 class CDxlGeneric;
00041 
00045 class CDxlConfig
00046 {
00047         public:
00048                 // All in SI units where possible
00049                 COptionInt              mID;
00050                 std::string     mDxlTypeStr;
00051                 COptionInt              mReturnDelay;   // Return delay time in microseconds
00052                 COptionDouble   mAngleLowerLimit; //motorAngleLowerlimit for 3mxl
00053                 COptionDouble   mAngleUpperLimit; //motorAngleUpperlimit for 3mxl
00054                 COptionBool             mClockwiseIsPositive;// Motor direction for 3mxl
00055 
00056                 //<ROBOTIS dynamixel specific>
00057                 COptionDouble   mVoltageLowerLimit;
00058                 COptionDouble   mVoltageUpperLimit;
00059                 COptionChar             mAlarmLED;
00060                 COptionChar             mAlarmShutdown;
00061                 COptionByte             mComplianceMargin;
00062                 COptionByte             mComplianceSlope;
00063                 COptionInt              mTempLimit;             // In degrees celcius
00064                 COptionBool             mLED;
00065                 COptionDouble   mTorqueLimit;
00066                 COptionDouble   mNullAngle;                             // Gives the natural 0-angle of the motor AFTER the sign convention, counted from the real 0-angle of the dynamixel (counted from -150 degrees from the mid point, so you will)
00067                 COptionWord             mPunch;
00068 
00069                 // Either calibdate or a direct angleLUT can be provided in the configuration.
00070                 // When such data is available, memory will be created for it.
00071                 EDxlCalibType   mCalibType;
00072                 double  mCalibData[DXLCONFIG_NUM_CALIBPOINTS];  // No. of items: DXLCONFIG_NUM_CALIBPOINTS. Gives the dynamixel position readout for every degree in the range 0 to 300 degrees (use the home-made calibration device to get this data!)
00073                 double  mAngleLUT[DXL_NUM_POSITIONS];           // No. of items: DXL_NUM_POSITIONS. Lookup table for angles. Generate this data with the automatic calibration device
00074                 //</ROBOTIS dynamixel specific>
00075                 //<3mxl specific>
00076                 COptionByte             m3mxlMode;
00077                 COptionByte             mWatchdogMode;
00078                 COptionByte             mWatchdogTime;
00079                 COptionByte             mWatchdogMult;
00080                 COptionByte             mStatusReturnLevel;
00081                 COptionDouble   mMotorConstant;
00082                 COptionDouble   mGearboxRatioMotor;
00083                 COptionDouble   mGearboxRatioJoint;
00084                 COptionWord             mEncoderCountMotor;
00085                 COptionDouble   mOffsetMotor;                                   //zero position of the motor in encoder counts
00086                 COptionDouble   mMaxUninitialisedMotorCurrent;
00087                 COptionDouble   mMaxMotorCurrent;
00088                 COptionWord             mEncoderCountJoint;
00089                 COptionDouble   mOffsetJoint;                                   //zero position of the joint in encoder counts
00090 //              COptionDouble   mMinJointAngle;
00091 //              COptionDouble   mMaxJointAngle;
00092                 COptionDouble   mZeroLengthSpring;
00093                 COptionDouble   mSpringStiffness;
00094                 COptionBool             mJointClockWiseIsPositive;
00095                 COptionDouble   mAcceleration;
00096                 
00097                 COptionDouble   mMaxPeakMotorCurrent;
00098                 COptionDouble   mMaxContinuousMotorCurrent;
00099                 COptionDouble   mMotorWindingTimeConstant;
00100                 COptionByte     mEncoderIndexLevelMotor;
00101                 COptionDouble   mWheelDiameter;
00102                 
00103                 COptionDouble   mPCurrent, mICurrent, mDCurrent, mILCurrent;
00104                 COptionDouble   mPPosition, mIPosition, mDPosition, mILPosition;
00105                 COptionDouble   mPSpeed, mISpeed, mDSpeed, mILSpeed;
00106                 COptionDouble   mPEnergy, mIEnergy, mDEnergy, mILEnergy;
00107                 COptionDouble   mPTorque, mITorque, mDTorque, mILTorque;
00108 
00109                 //</3mxl specific>
00110                 CDxlConfig();
00111                 ~CDxlConfig();
00112 
00113                 CDxlConfig*     setID(const int ID);                                    // useful in passing this config pointer right after changing the ID.
00114                 bool            readConfig(const CConfigSection &configNode);
00115                 int                     configureDynamixel(CDxlGeneric* dxl);   // call configureDynamixel() AFTER calling CDynamixel::init()!
00116 };
00117 
00123 class CDxlGroupConfig
00124 {
00125         protected:
00126                 CDxlConfig      mDxlConfigs[MAX_NUM_DYNAMIXELS];
00127                 int                     mNumDynamixels;
00128         public:
00129                 CDxlGroupConfig()                                                               {mNumDynamixels=0;}
00130                 int                     getNumDynamixels()                                      {return mNumDynamixels;}
00131                 CDxlConfig*     getDynamixelConfig(const int index)     {return &mDxlConfigs[index];}
00132 
00133                 // Automatic config readout from XML file
00134                 bool            readFromXML(const std::string &filename);
00135 
00136                 // If you want, you can fill the config by hand (for debugging)
00137                 /*
00138                 int                     addDynamixel(const int ID)
00139                 {
00140                         mDxlConfigs[mNumDynamixels].mID = ID;
00141                         return mNumDynamixels++;
00142                 }
00143                 */
00144                 int                     addDynamixel(CDxlConfig* config) //< store dynamixel config in group config object
00145                 {
00146                         mDxlConfigs[mNumDynamixels] = *config;
00147                         return mNumDynamixels++;
00148                 }
00149 };
00150 
00151 
00152 #endif //__DYNAMIXELCONFIG_H_INCLUDED__


threemxl
Author(s):
autogenerated on Fri Aug 28 2015 13:21:08