3mxlControlTable.h
Go to the documentation of this file.
00001 
00002 #ifndef __3MXLCONTROLTABLE_H_INCLUDED__
00003 #define __3MXLCONTROLTABLE_H_INCLUDED__
00004 
00005 /*************************************************************************
00006 Organisation    :       Delft University Of Technology
00007                                         Biomechanical Engineering
00008                                         Dutch Biorobotics Lab
00009 
00010 Project                 : 3MXL
00011 
00012 Author                  : Dries Hulens / Eelko van Breda / Guus Liqui Lung / Daniel Karssen
00013 
00014 initial Date    : 09 March 2010
00015                                   02 December 2010
00016                                   28 January 2010
00017 
00018 current Version : 2.1
00019 
00020 Filename :              : 3mxlControlTable.h
00021 
00022 Description             : contains constants for the controltable used in the
00023                                         Dynamixelprotocol
00024 
00025 *************************************************************************/
00026 
00027 // original Dynamixel command instructions:
00028 #define NO_INSTRUCTION                                                  0x00
00029 #define PING                                                                    0x01
00030 #define READ_DATA                                                               0x02
00031 #define WRITE_DATA                                                              0x03
00032 #define REG_WRITE                                                               0x04
00033 #define ACTION                                                                  0x05
00034 #define RESET                                                                   0x06
00035 #define SYNC_WRITE                                                              0x83
00036 
00037 // instructions added by GLL for 3Mxel, not fully implemented yet
00038 #define WRITE_MOTOR_PARAMS                                              0xA0    // motor constant, gearboxratio etc
00039 #define WRITE_JOINT_PARAMS                                              0xA1    // encoder resol, spring etc
00040 #define WRITE_SEA_SETPOINTS                                             0xA2    // PD gains position control mode
00041 #define SET_JOINT_TYPE                                                  0xA3    // left/right hip/knee
00042 
00043 // broadcast ID to address multiple 3Mxels
00044 #define BROADCAST_ID                                                    0xFE
00045 
00046 // packet types
00047 #define NORMAL_PACKET_TYPE                                              0x00
00048 #define BROADCAST_PACKET_TYPE                                   0x01
00049 
00053 #define POSITION_MODE                                                   0       // uses one motor and encoder with position controller
00054 #define SPEED_MODE                                                              1       // uses one motor and encoder with speed controller
00055 #define CURRENT_MODE                                                    2       // uses one motor and encoder with current controller
00056 #define TORQUE_MODE                                                             3       // uses one motor and encoder with torque controller
00057 #define SEA_MODE                                                                4       // uses one motor and two encoders with SEA controller
00058 #define PWM_MODE                                                                5       // uses one motor and encoder with PWM controller, no PID, just PWM !!
00059 
00060 #define INDEX_INIT                                                              6       // reset counter on index pulse, turn motor with given torque in M3XL_DESIRED_TORQUE_L
00061 #define EXTERNAL_INIT                                                   7       // reset counter on external io pulse, turn motor with given torque in M3XL_DESIRED_TORQUE_L
00062 #define ZERO_SPEED_INIT                                                 8       // reset counter when jointspeed reaches zero (endstop), turn motor with given torque in
00063                                                                                                         //      M3XL_DESIRED_TORQUE_L
00064 #define SEA_INIT                                                                9       // reset counter of joint on index pulse and reset counter of motor on the next motor pulse.
00065                                                                                                         //      Turn motor with given torque in M3XL_DESIRED_TORQUE_L
00066 #define MANUAL_INIT                                                             10      // reset counter of joint on index pulse and reset counter of motor on the next motor pulse.
00067                                                                                                         //      manually rotate motor/joint
00068 #define TIME_OUT_INIT                                                   11      // reset counter of joint after a timeou value. Turn motor with given torque in M3XL_DESIRED_TORQUE_L
00069 #define STOP_MODE                                                               12      // do nothing, no actuated motors
00070 #define HOME_SWITCH_AND_INDEX_INIT                              13      // move to external home switch and reset counter on index in SPEED_MODE
00071 #define CURRENT_POS_AND_SPEED_MODE                              14      // uses current control based on position and motor torque
00072 #define START_UP_MODE                                                   15
00073 #define SINUSOIDAL_POSITION_MODE                                16
00074 #define TEST_MODE                                                               17      // for general testing
00075 
00076 #define NR_OF_CONTROL_MODES                                             TORQUE_MODE+1
00077 
00079 // Standard Dynamixel status errorcode bits
00080 // They are reurned as standard dynamixel ERRR_CODE in a status packet
00081 // and are now stored at  M3XL_DONE  = 0xA5
00082 #define M3XL_NO_ERROR                                                   0b00000000
00083 #define M3XL_INSTRUCTION_ERROR                                  0b01000000
00084 #define M3XL_OVERLOAD_ERROR                                             0b00100000
00085 #define M3XL_CHECKSUM_ERROR                                             0b00010000
00086 #define M3XL_RANGE_ERROR                                                0b00001000
00087 #define M3XL_OVERHEATING_ERROR                                  0b00000100
00088 #define M3XL_ANGLE_LIMIT_ERROR                                  0b00000010
00089 #define M3XL_INPUT_VOLTAGE_ERROR                                0b00000001
00090 
00096 #define M3XL_STATUS_EEPROM_ERROR                                0x80
00097 #define M3XL_STATUS_NOT_INITIALIZED                             0x81
00098 #define M3XL_STATUS_EM_STOP_ERROR                               0x82
00099 #define M3XL_STATUS_INIT_TIME_OUT_ERROR                 0x83
00100 #define M3XL_STATUS_MAX_POS_ERROR                               0x84
00101 #define M3XL_STATUS_MAX_TORQUE_ERROR                    0x85
00102 #define M3XL_STATUS_MAX_CURRENT_ERROR                   0x86
00103 #define M3XL_STATUS_MOTOR_STUCK_ERROR                   0x87
00104 #define M3XL_STATUS_JOINT_STUCK_ERROR                   0x88
00105 #define M3XL_STATUS_PROTOCOL_TIME_OUT_ERROR             0x89
00106 
00107 #define M3XL_STATUS_MOVING                                              0X90
00108 #define M3XL_STATUS_MOVE_DONE                                   0X91
00109 #define M3XL_STATUS_INITIALIZE_BUSY                             0X92
00110 #define M3XL_STATUS_INIT_DONE                                   0x93
00111 #define M3XL_STATUS_POS_MODE_EXECUTING                  0x94
00112 #define M3XL_STATUS_POS_MODE_DONE                               0x95
00113 #define M3XL_STATUS_SPEED_MODE_EXECUTING                0x96
00114 #define M3XL_STATUS_SPEED_MODE_DONE                             0x97
00115 #define M3XL_STATUS_TORQUE_MODE_EXECUTING               0x98
00116 #define M3XL_STATUS_TORQUE_MODE_DONE                    0x99
00117 #define M3XL_STATUS_CURRENT_MODE_EXECUTING              0x9A
00118 #define M3XL_STATUS_CURRENT_MODE_DONE                   0x9B
00119 #define M3XL_STATUS_SEA_MODE_EXECUTING                  0x9C
00120 #define M3XL_STATUS_SEA_MODE_DONE                               0x9D
00121 #define M3XL_STATUS_PWM_MODE_EXECUTING                  0x9E
00122 #define M3XL_STATUS_PWM_MODE_DONE                               0x9F
00123 #define M3XL_STATUS_SINUSOIDAL_POS_MODE_EXECUTING     0xA0
00124 #define M3XL_STATUS_SINUSOIDAL_POS_MODE_DONE          0xA1
00125 #define M3XL_STATUS_IDLE_STATE                                  0xA0
00126 
00128 // used for signaling when action is in progress
00129 #define M3XL_ACTION_BUSY                                                0x00
00130 #define M3XL_ACTION_DONE                                                0xFF
00131 
00132 // default IDs for address M3XL_ID
00133 #define DEFAULT_3MXL_ID_1                                               0x64
00134 #define DEFAULT_3MXL_ID_2                                               0x65
00135 
00136 // status return level Control table address M3XL_STATUS_RETURN_LEVEL
00137 #define M3XL_STATUS_RETURN_NONE                                 0x00
00138 #define M3XL_STATUS_RETURN_READ_DATA                    0x01
00139 #define M3XL_STATUS_RETURN_ALL                                  0x02    //Same as dynamixel
00140 
00141 // 3Mxel joints types for address M3XL_JOINT_TYPE_H
00142 #define JOINT_TYPE_WHEEL                                                0x01
00143 #define JOINT_TYPE_ARM                                                  0x02
00144 #define JOINT_TYPE_GRIPPER                                              0x03
00145 #define JOINT_TYPE_DIRECTDRIVE                                  0x04
00146 #define JOINT_TYPE_SEA                                                  0x05
00147 #define JOINT_TYPE_LINEAR                                               0x06
00148 #define JOINT_TYPE_PASSIVE                                              0x07
00149 #define JOINT_TYPE_UNKNOWN                                              0x0A
00150 
00151 // maximum allowable motorcurrent, determined by H-bridge
00152 #ifdef M3XL_MINI
00153         #define M3XL_MAX_MOTOR_CURRENT                                  2.8
00154 #else
00155         #define M3XL_MAX_MOTOR_CURRENT                                  40.0
00156 #endif
00157 
00158 #define M_PI                                                                    3.14159265358979323846
00159 
00160 //***************************************************************************
00161 // HERE ARE THE ADRESSES OF THE ELEMENTS IN THE TABLE
00162 //***************************************************************************
00163 
00164 #define M3XL_JOINT_TYPE_L                                               0x00
00165 #define M3XL_JOINT_TYPE_H                                               0x01 // The high byte of M3XL_JOINT_TYPE is now used to store the actual jointtype
00166 #define M3XL_VERSION_FIRMWARE                                   0x02
00167 #define M3XL_ID                                                                 0x03
00168 #define M3XL_STATUS_RETURN_LEVEL                                0x10    //Same as dynamixel
00169 
00171 //#define BAUD_RATE_L                                                   0x04
00172 //#define RETURN_DELAY_TIME                                             0x05
00173 //#define CW_ANGLE_LIMIT_L                                              0x06
00174 //#define CW_ANGLE_LIMIT_H                                              0x07
00175 //#define CCW_ANGLE_LIMIT_L                                             0x08
00176 //#define CCW_ANGLE_LIMIT_H                                             0x09
00177 //
00178 //#define LIMIT_TEMP_HIGH                                               0x0B
00179 //#define LIMIT_VOLTAGE_LOW                                             0x0C
00180 //#define LIMIT_VOLTAGE_HIGH                                    0x0D
00181 //#define MAX_TORQUE_L                                                  0x0E
00182 //#define MAX_TORQUE_H                                                  0x0F
00183 //#define STATUS_RETURN_LEVEL                                   0x10
00184 //#define ALARM_LED                                                             0x11
00185 //#define ALARM_SHUTDOWN                                                0x12
00186 //
00187 //#define TORQUE_ENABLE                                                 0x18
00188 //#define LED                                                                   0x19
00189 //#define CW_COMPILANCE_MARGIN                                  0x1A
00190 //#define CCW_COMPILANCE_MARGIN                                 0x1B
00191 //#define CW_COMPILANCE_SLOPE                                   0x1C
00192 //#define CCW_COMPILANCE_SLOPE                                  0x1D
00193 //#define GOAL_POSITION_L                                               0x1E
00194 //#define GOAL_POSITION_H                                               0x1F
00195 //#define MOVING_SPEED_L                                                0x20
00196 //#define MOVING_SPEED_H                                                0x21
00197 //#define TORQUE_LIMIT_L                                                0x22
00198 //#define TORQUE_LIMIT_H                                                0x23
00199 //#define PRESENT_POSITION_L                                    0x24
00200 //#define PRESENT_POSITION_H                                    0x25
00201 //#define PRESENT_SPEED_L                                               0x26
00202 //#define PRESENT_SPEED_H                                               0x27
00203 //#define PRESENT_LOAD_L                                                0x28
00204 //#define PRESENT_LOAD_H                                                0x29
00205 //#define PRESENT_VOLTAGE                                               0x2A
00206 //#define PRESENT_TEMP                                                  0x2B
00207 //#define REGISTERED_INSTRUCTION                                0x2C
00208 //
00209 //#define MOVING                                                                0x2E
00210 //#define MXL_LOCK                                                              0x2F
00211 //#define PUNCH_L                                                               0x30
00212 //#define PUNCH_H                                                               0x31
00214 
00216 #define M3XL_BAUD_RATE_L                                                0x32    //Baudrate in baud
00217 #define M3XL_BAUD_RATE_M                                                0x33
00218 #define M3XL_BAUD_RATE_H                                                0x34
00219 #define M3XL_RETURN_DELAY_TIME                                  0x35    //In dynamixel dimension
00220 #define M3XL_CONTROL_MODE                                               0x36    //Describes behaviour of the 3mxl
00221 
00222 //watchdog resets on arrival of new personal packet or broadcast (Not yet implemented!)
00223 #define M3XL_WATCHDOG_MODE                                              0x37    //what to do of watchdog triggers
00224 #define M3XL_WATCHDOG_TIME_MS                                   0x38    //time setting for watchdog = ms x multiplier
00225 #define M3XL_WATCHDOG_TIMER_MUL                                 0x39
00226 
00227 //--- <Direct drive and SEA mode parameters>
00228 #define M3XL_MOTOR_CONSTANT_L                                   0x3A    //dimension 10^-4*Nm/A
00229 #define M3XL_MOTOR_CONSTANT_H                                   0x3B
00230 #define M3XL_MAX_CONTINUOUS_MOTOR_CURRENT_L             0x3C    // MAX continuous Current in 10mA
00231 #define M3XL_MAX_CONTINUOUS_MOTOR_CURRENT_H             0x3D
00232 #define M3XL_MAX_MOTOR_PEAK_CURRENT_L                   0x3E    // stall Current in 10mA
00233 #define M3XL_MAX_MOTOR_PEAK_CURRENT_H                   0x3F
00234 #define M3XL_MOTOR_WINDING_TIME_CONSTANT_L              0x40    // motorwinding temperature time constant in 0.01 sec
00235 #define M3XL_MOTOR_WINDING_TIME_CONSTANT_H              0x41
00236 #define M3XL_GEARBOX_RATIO_MOTOR_L                              0x42    // ratio between motor and joint (turns of motor rev for one joint revolution), times 10
00237 #define M3XL_GEARBOX_RATIO_MOTOR_H                              0x43
00238 #define M3XL_ENCODER_COUNT_MOTOR_L                              0x44    // encoder counts quadrature
00239 #define M3XL_ENCODER_COUNT_MOTOR_H                              0x45
00240 #define M3XL_OFFSET_MOTOR_L                                             0X46    // zero position of the motor in mRad
00241 #define M3XL_OFFSET_MOTOR_H                                             0X47
00242 #define M3XL_MOTOR_ENC_DIRECTION                                0x48    // clockwise is positive {0,1}
00243 #define M3XL_MOTOR_ENC_INDEX_LEVEL                              0x49    // index at LOW AB or HIGH AB pulses
00244 #define M3XL_CW_MOTOR_ANGLE_LIMIT_L                             0x4A    // RW Position in 1 mRad
00245 #define M3XL_CW_MOTOR_ANGLE_LIMIT_H                             0x4B
00246 #define M3XL_CCW_MOTOR_ANGLE_LIMIT_L                    0x4C    // RW Position in 1 mRad
00247 #define M3XL_CCW_MOTOR_ANGLE_LIMIT_H                    0x4D
00248 //--- </Direct drive and SEA mode>
00249 
00250 //--- <Series Elastic Mode parameters> (normally not used in direct drive mode)
00251 #define M3XL_GEARBOX_RATIO_JOINT_L                              0x4E    // ratio between encoder and joint (turns of encoder rev for one joint revolution), times 10
00252 #define M3XL_GEARBOX_RATIO_JOINT_H                              0x4F
00253 #define M3XL_ENCODER_COUNT_JOINT_L                              0x50    // encoder counts quadrature
00254 #define M3XL_ENCODER_COUNT_JOINT_H                              0x51
00255 #define M3XL_OFFSET_JOINT_L                                             0x52    // zero position of the joint in mRad
00256 #define M3XL_OFFSET_JOINT_H                                             0x53
00257 #define M3XL_MAX_JOINT_TORQUE_L                                 0x54    // RW Torque in 0,001 Nm (mNm)
00258 #define M3XL_MAX_JOINT_TORQUE_H                                 0x55
00259 #define M3XL_CW_JOINT_ANGLE_LIMIT_L                             0x56    // RW Position in 1 mRad
00260 #define M3XL_CW_JOINT_ANGLE_LIMIT_H                             0x57
00261 #define M3XL_CCW_JOINT_ANGLE_LIMIT_L                    0x58    // RW Position in 1 mRad
00262 #define M3XL_CCW_JOINT_ANGLE_LIMIT_H                    0x59
00263 #define M3XL_ZERO_LENGTH_SPRING_L                               0x5A    // TODO:dimension?
00264 #define M3XL_ZERO_LENGTH_SPRING_H                               0x5B
00265 #define M3XL_SPRING_STIFFNESS_L                                 0x5C    // cNm/rad
00266 #define M3XL_SPRING_STIFFNESS_H                                 0x5D
00267 #define M3XL_JOINT_ENC_DIRECTION                                0x5E    // clockwiseispositive {0,1}
00268 #define M3XL_JOINT_ENC_INDEX_LEVEL                              0x5F    // index at LOW AB or HIGH AB pulses
00269 //--- </Series Elastic Mode>
00270 
00271 //--- <Status information>
00272 #define M3XL_VOLTAGE_L                                                  0x60    // RO Voltage in 10mV
00273 #define M3XL_VOLTAGE_H                                                  0x61
00274 #define M3XL_CURRENT_L                                                  0x62    // RO Current in 10mA
00275 #define M3XL_CURRENT_H                                                  0x63
00276 #define M3XL_TORQUE_L                                                   0x64    // RO Torque in 0,001 Nm (mNm)
00277 #define M3XL_TORQUE_H                                                   0x65
00278 #define M3XL_ANGLE_L                                                    0x66    // RO Angle in 1 mRad
00279 #define M3XL_ANGLE_H                                                    0x67
00280 #define M3XL_ANGULAR_RATE_L                     0x68    // RO Angular Speed in 10mRad/s (cRad)/s
00281 #define M3XL_ANGULAR_RATE_H                     0x69
00282 #define M3XL_POSITION_32_1                                              0x6A     // 32 bits actual position in mm
00283 #define M3XL_POSITION_32_2                                              0x6B
00284 #define M3XL_POSITION_32_3                                              0x6C
00285 #define M3XL_POSITION_32_4                                              0x6D
00286 #define M3XL_SPEED_L                                                    0x6E    // speed in 0.1 mm/s
00287 #define M3XL_SPEED_H                                                    0x6F
00288 #define M3XL_LINEAR_SPEED_L                                             M3XL_SPEED_L    // speed in mm/s
00289 #define M3XL_LINEAR_SPEED_H                                             M3XL_SPEED_H
00290 //--- </Status information>
00291 
00292 //--- <Setpoints for PID>
00293 // the next 3 parameters MotorCurrent, Pgain and Dgain can be sent in one syncwrite packet
00294 #define M3XL_DESIRED_CURRENT_L                                  0x70    // RW Current in 10mA
00295 #define M3XL_DESIRED_CURRENT_H                                  0x71
00296 
00297 // the next 5 parameters can be sent in one syncwrite packet
00298 #define M3XL_P_CURRENT_L                                                0x72    // when start writing at this address
00299 #define M3XL_P_CURRENT_H                                                0x73    // all PID CURRENT_MODE params should be sent, 10 bytes
00300 #define M3XL_D_CURRENT_L                                                0x74
00301 #define M3XL_D_CURRENT_H                                                0x75
00302 #define M3XL_I_CURRENT_L                                                0x76
00303 #define M3XL_I_CURRENT_H                                                0x77
00304 #define M3XL_IL_CURRENT_L                                               0x78
00305 #define M3XL_IL_CURRENT_H                                               0x79
00306 #define M3XL_PID_CURRENT_SCALE_L                                0x7A
00307 #define M3XL_PID_CURRENT_SCALE_H                                0x7B
00308 
00309 #define M3XL_DESIRED_POSITION_32_1                              0x7C   // RW 32 bits position in mm
00310 #define M3XL_DESIRED_POSITION_32_2                              0x7D
00311 #define M3XL_DESIRED_POSITION_32_3                              0x7E
00312 #define M3XL_DESIRED_POSITION_32_4                              0x7F
00313 
00314 #define M3XL_DESIRED_ACCEL_L                                    0x80    // RW Speed in 10mRad/s (cRad)/s
00315 #define M3XL_DESIRED_ACCEL_H                                    0x81
00316 #define M3XL_DESIRED_ANGULAR_ACCEL_L                    M3XL_DESIRED_ACCEL_L   // RW Speed in 10mRad/s (cRad)/s
00317 #define M3XL_DESIRED_ANGULAR_ACCEL_H                    M3XL_DESIRED_ACCEL_H
00318 
00319 // the next 5 parameters Angle, Speed, Torque, Pgain and Dgain can be sent in one syncwrite packet
00320 #define M3XL_DESIRED_ANGLE_L                                    0x82    // RW Position in 1 mRad
00321 #define M3XL_DESIRED_ANGLE_H                                    0x83
00322 
00323 // entry names changed, old ones kept for compatibility
00324 #define M3XL_DESIRED_SPEED_L                                    0x84    // RW Speed in 10mRad/s (cRad)/s
00325 #define M3XL_DESIRED_SPEED_H                                    0x85
00326 #define M3XL_DESIRED_ANGULAR_RATE_L                             M3XL_DESIRED_SPEED_L   // RW Speed in 10mRad/s (cRad)/s
00327 #define M3XL_DESIRED_ANGULAR_RATE_H                             M3XL_DESIRED_SPEED_H
00328 
00329 #define M3XL_DESIRED_TORQUE_L                                   0x86    // RW Torque in 0,001 Nm (mNm)
00330 #define M3XL_DESIRED_TORQUE_H                                   0x87
00331 
00332 // the next 5 PID parameters can be sent in one syncwrite packet
00333 #define M3XL_P_POSITION_L                                               0x88    // when start writing at this address
00334 #define M3XL_P_POSITION_H                                               0x89    // all PID POSITION_MODE params should be sent, 10 bytes
00335 #define M3XL_D_POSITION_L                                               0x8A
00336 #define M3XL_D_POSITION_H                                               0x8B
00337 #define M3XL_I_POSITION_L                                               0x8C
00338 #define M3XL_I_POSITION_H                                               0x8D
00339 #define M3XL_IL_POSITION_L                                              0x8E
00340 #define M3XL_IL_POSITION_H                                              0x8F
00341 #define M3XL_PID_POSITION_SCALE_L                               0x90
00342 #define M3XL_PID_POSITION_SCALE_H                               0x91
00343 
00344 // the next 5 PID parameters can be sent in one syncwrite packet
00345 #define M3XL_P_SPEED_L                                                  0x92    // when start writing at this address
00346 #define M3XL_P_SPEED_H                                                  0x93    // all PID SPEED_MODE params should be sent, 10 bytes
00347 #define M3XL_D_SPEED_L                                                  0x94
00348 #define M3XL_D_SPEED_H                                                  0x95
00349 #define M3XL_I_SPEED_L                                                  0x96
00350 #define M3XL_I_SPEED_H                                                  0x97
00351 #define M3XL_IL_SPEED_L                                                 0x98
00352 #define M3XL_IL_SPEED_H                                                 0x99
00353 #define M3XL_PID_SPEED_SCALE_L                                  0x9A
00354 #define M3XL_PID_SPEED_SCALE_H                                  0x9B
00355 
00356 // the next 5 PID parameters can be sent in one syncwrite packet
00357 #define M3XL_P_TORQUE_L                                                 0x9C    // when start writing at this address
00358 #define M3XL_P_TORQUE_H                                                 0x9D    // all PID TORQUE_MODE params should be sent, 10 bytes
00359 #define M3XL_D_TORQUE_L                                                 0x9E
00360 #define M3XL_D_TORQUE_H                                                 0x9F
00361 #define M3XL_I_TORQUE_L                                                 0xA0
00362 #define M3XL_I_TORQUE_H                                                 0xA1
00363 #define M3XL_IL_TORQUE_L                                                0xA2
00364 #define M3XL_IL_TORQUE_H                                                0xA3
00365 #define M3XL_PID_TORQUE_SCALE_L                                 0xA4
00366 #define M3XL_PID_TORQUE_SCALE_H                                 0xA5
00367 
00368 #define M3XL_DESIRED_PWM_L                                              0xA6
00369 #define M3XL_DESIRED_PWM_H                                              0xA7
00370 //--- </Setpoints for PID>
00371 
00372 #define M3XL_STATUS                             0xA8
00373 #define M3XL_INITIALIZED                        0xA9
00374 
00375 #define M3XL_STOP_PROTOCOL_HANDLER              0xAA    // quit protocolmode and switch to terminal mode
00376 
00377 // added for linear type of joints
00378 #define M3XL_DESIRED_LINEAR_SPEED_L                             0xAB    // speed in mm/s
00379 #define M3XL_DESIRED_LINEAR_SPEED_H                             0xAC    
00380 #define M3XL_DESIRED_LINEAR_ACCEL_L                             0xAD    // accel in mm/s2
00381 #define M3XL_DESIRED_LINEAR_ACCEL_H                             0xAE
00382 #define M3XL_MAX_JERK_L                         0xAF    // jerk in mm/s3
00383 #define M3XL_MAX_JERK_H                         0xB0
00384 
00385 #define LAST_MESSAGE_ADDRESS                    0xB1    // local buffering for action after regwrite
00386 #define LAST_MESSAGE_LENGTH                     0xB2
00387 
00388 #define M3XL_WHEEL_DIAMETER_L                   0xB3    // wheeldiameter in mm
00389 #define M3XL_WHEEL_DIAMETER_H                   0xB4
00390 
00391 // next entries are for Underwater robot
00392 #define M3XL_SINUSOIDAL_FREQUENCY_L                             0xB5    // in 10mHz
00393 #define M3XL_SINUSOIDAL_FREQUENCY_H                             0xB6    
00394 #define M3XL_SINUSOIDAL_AMPLITUDE_L             0xB7    // in mRad
00395 #define M3XL_SINUSOIDAL_AMPLITUDE_H             0xB8
00396 #define M3XL_SINUSOIDAL_PHASE_ANGLE_L                   0xB9    // in mRad
00397 #define M3XL_SINUSOIDAL_PHASE_ANGLE_H                   0xBA
00398 
00399 // next entries are used to verify the index position of the motor
00400 #define M3XL_ACQUIRE_INDEX_POSITION             0xBA
00401 #define M3XL_INDEX_POSITION_32_1                                0xBB   // RW 32 bits index position in mm
00402 #define M3XL_INDEX_POSITION_32_2                                0xBC
00403 #define M3XL_INDEX_POSITION_32_3                                0xBD
00404 #define M3XL_INDEX_POSITION_32_4                                0xBE
00405 
00406 #define M3XL_LOG_ARRAY_SIZE                                             500             // also declared as LOG_ARRAY_SIZE in SystemDefs.h
00407 #define M3XL_NR_OF_BYTES_PER_SAMPLE                             22              // the amount of bytes in one sample
00408 #define M3XL_NR_OF_SAMPLES_PER_BLOCK                    5               // the amount of samples in a block
00409 #define M3XL_NR_OF_BLOCKS                                               (M3XL_LOG_ARRAY_SIZE / M3XL_NR_OF_SAMPLES_PER_BLOCK)            // the amount of blocks in a log
00410 #define M3XL_NR_OF_BYTES_PER_BLOCK                              (M3XL_NR_OF_SAMPLES_PER_BLOCK * M3XL_NR_OF_BYTES_PER_SAMPLE)
00411 
00412 #define M3XL_ENABLE_DATA_LOGGER                                 0xBF    // setting this to 1 enables the datalogger for that motor.
00413 #define M3XL_LOG_DATA_INTERVAL                                  0xC0    // loginterval in ms                                                                                            
00414                                                                                                                 // the entry other motor will be set to 0!
00415 #define M3XL_DATA_LOGGER                                                0xC1    // reading from this location starts reporting data by datalogger
00416                                                                                                                 // which data is logged depends on the control mode
00417                                                                                                                 // data is split in blocks of 5 readings of 20 bytes
00419                                                                                                                 //struct dataLoggerOutputType
00420                                                                                                                 //{
00421                                                                                                                 //      unsigned int sampleTime;        // 16 bits, 2 bytes
00422                                                                                                                 //      float PWMDutyCycle;                     // 32 bits, 4 bytes
00423                                                                                                                 //      float motorCurrent;                     // 32 bits, 4 bytes
00424                                                                                                                 //      float vBus;                                     // 32 bits, 4 bytes
00425                                                                                                                 //      float desiredValue;                     // 32 bits, 4 bytes
00426                                                                                                                 //      float actualValue;                      // 32 bits, 4 bytes
00427                                                                                                                 //};
00428                                                                                                                 // The value written to M3XL_DATA_LOGGER specifies the block number
00429                                                                                                                 // e.g. : 1   : read block 1 samples 1-5
00430                                                                                                                 // e.g. : 2   : read block 2 samples 6-10
00431                                                                                                                 // e.g. : 100 : read block 100 samples 496-500
00432 #define M3XL_BUS_VOLTAGE_L                                              0xC2    // RO Bus Voltage in 10mV
00433 #define M3XL_BUS_VOLTAGE_H                                              0xC3
00434 #define M3XL_MOTOR_CURRENT_L                                            0xC4    // Motorcurrent in cA
00435 #define M3XL_MOTOR_CURRENT_H                                            0xC5
00436 #define M3XL_ANA1_VOLTAGE_L                                             0xC6    // RO Analog Voltage in 10mV
00437 #define M3XL_ANA1_VOLTAGE_H                                             0xC7
00438 #define M3XL_ANA2_VOLTAGE_L                                             0xC8    // RO Analog Voltage in 10mV
00439 #define M3XL_ANA2_VOLTAGE_H                                             0xC9
00440 #define M3XL_ANA3_VOLTAGE_L                                             0xCA    // RO Analog Voltage in 10mV
00441 #define M3XL_ANA3_VOLTAGE_H                                             0xCB
00442 #define M3XL_ANA4_VOLTAGE_L                                             0xCC    // RO Analog Voltage in 10mV
00443 #define M3XL_ANA4_VOLTAGE_H                                             0xCD
00444 
00445 // old
00446 // #define M3XL_SYNC_READ_INDEX                    0xCA
00447 
00448 // new on 10-12-2013
00449 #define M3XL_SYNC_READ_INDEX                                            0xD0
00450 
00451 // *** ALTERNATIVE CONTROL TABLE IDS FOR Michiel's V4 ***
00452 // the next 5 parameters can be sent in one syncwrite packet
00453 #define M3XL_P_ENERGY_L                                                 0xC4    // when start writing at this address
00454 #define M3XL_P_ENERGY_H                                                 0xC5    // all PID ENERGY_MODE params should be sent, 10 bytes
00455 #define M3XL_D_ENERGY_L                                                 0xC6
00456 #define M3XL_D_ENERGY_H                                                 0xC7
00457 #define M3XL_I_ENERGY_L                                                 0xC8
00458 #define M3XL_I_ENERGY_H                                                 0xC9
00459 #define M3XL_IL_ENERGY_L                                                0xCA
00460 #define M3XL_IL_ENERGY_H                                                0xCB
00461 #define M3XL_PID_ENERGY_SCALE_L                                         0xCC
00462 #define M3XL_PID_ENERGY_SCALE_H                                         0xCD
00463 
00464 #define M3XL_REFERENCE_ENERGY_L                                         0xCE    // RW Energy in mJ
00465 #define M3XL_REFERENCE_ENERGY_H                                         0xCF
00466 // *** END ALTERNATIVE CONTROL TABLE IDS FOR Michiel's V4 ***
00467 
00468 //***************************************************************************
00469 // END OF TABLE
00470 //***************************************************************************
00471 
00472 #endif //__3MXLCONTROLTABLE_H_INCLUDED__


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