|
| 1 | +//==================================================================== |
| 2 | +//Project Lynxmotion Phoenix |
| 3 | +//Description: |
| 4 | +// This is the hardware configuration file for the |
| 5 | +// Version 2 PhantomX Quad robot. |
| 6 | +// Will first define to use their commander unit. |
| 7 | +// |
| 8 | +//Date: June 29, 2013 |
| 9 | +// |
| 10 | +//==================================================================== |
| 11 | +#ifndef QUAD_CFG_H |
| 12 | +#define QUAD_CFG_H |
| 13 | + |
| 14 | +#define QUADMODE // We are building for quad support... |
| 15 | +#define ADJUSTABLE_LEG_ANGLES |
| 16 | +#define DBGSerial Serial |
| 17 | +//================================================================================================================================== |
| 18 | +// Define which input classes we will use. If we wish to use more than one we need to define USEMULTI - This will define a forwarder |
| 19 | +// type implementation, that the Inputcontroller will need to call. There will be some negotion for which one is in contol. |
| 20 | +// |
| 21 | +// If this is not defined, The included Controller should simply implement the InputController Class... |
| 22 | +//================================================================================================================================== |
| 23 | +//#define USEMULTI |
| 24 | +//#define USEXBEE // only allow to be defined on Megas... |
| 25 | +//#define USEPS2 |
| 26 | +#define USECOMMANDER |
| 27 | + |
| 28 | +// Global defines to control which configuration we are using. Note: Only define one of these... |
| 29 | +// |
| 30 | +// Which type of control(s) do you want to compile in |
| 31 | +#ifdef USEXBEE // some options only valid if running with XBEE stuff |
| 32 | +#define XBEE_DEBUG_OUTPUT // use our xbee serial class to do debug stuff |
| 33 | +#define DBGSerial XBDSerial |
| 34 | +#endif |
| 35 | +#define DBGSerial Serial |
| 36 | + |
| 37 | +// Define other optional compnents to be included or not... |
| 38 | +//#define PHANTOMX_V2 // Some code may depend on it being a V2 PhantomX |
| 39 | +#define cFemurHornOffset1 -70 |
| 40 | +#define cTibiaHornOffset1 380 |
| 41 | +#define cRRTibiaInv 0 |
| 42 | +#define cRMTibiaInv 0 |
| 43 | +#define cRFTibiaInv 0 |
| 44 | +#define cLRTibiaInv 1 |
| 45 | +#define cLMTibiaInv 1 |
| 46 | +#define cLFTibiaInv 1 |
| 47 | + |
| 48 | +#define BALANCE_DELAY 25 // don't add as much as the default here. |
| 49 | + |
| 50 | +//=================================================================== |
| 51 | +// Debug Options |
| 52 | +#ifdef DBGSerial |
| 53 | +//#define OPT_TERMINAL_MONITOR |
| 54 | +//#define OPT_FIND_SERVO_OFFSETS // Only useful if terminal monitor is enabled |
| 55 | +//#define OPT_PYPOSE |
| 56 | +#endif |
| 57 | + |
| 58 | +//#define DEBUG_IOPINS |
| 59 | +#ifdef DEBUG_IOPINS |
| 60 | +#define DebugToggle(pin) {digitalWrite(pin, !digitalRead(pin));} |
| 61 | +#define DebugWrite(pin, state) {digitalWrite(pin, state);} |
| 62 | +#else |
| 63 | +#define DebugToggle(pin) {;} |
| 64 | +#define DebugWrite(pin, state) {;} |
| 65 | +#endif |
| 66 | + |
| 67 | + |
| 68 | +// Also define that we are using the AX12 driver |
| 69 | +#define USE_AX12_DRIVER |
| 70 | +#define OPT_BACKGROUND_PROCESS // The AX12 has a background process |
| 71 | +//#define OPT_GPPLAYER |
| 72 | + |
| 73 | + |
| 74 | +//================================================================================================================================== |
| 75 | +//================================================================================================================================== |
| 76 | +//================================================================================================================================== |
| 77 | +// PhantomX |
| 78 | +//================================================================================================================================== |
| 79 | +//[SERIAL CONNECTIONS] |
| 80 | + |
| 81 | +//==================================================================== |
| 82 | +// XBEE on non mega??? |
| 83 | +#define XBeeSerial Serial |
| 84 | +#define XBEE_BAUD 38400 |
| 85 | +#define DISP_VOLTAGE // User wants the Battery voltage to be displayed... |
| 86 | +#define DISP_VOLTAGE_TIME 1000 // how often to check and report in millis |
| 87 | +//-------------------------------------------------------------------- |
| 88 | +//[Arbotix Pin Numbers] |
| 89 | +#define SOUND_PIN 1 //0xff // Tell system we have no IO pin... |
| 90 | +#define PS2_DAT A0 |
| 91 | +#define PS2_CMD A1 |
| 92 | +#define PS2_SEL A2 |
| 93 | +#define PS2_CLK A3 |
| 94 | + |
| 95 | +// Define Analog pin and minimum voltage that we will allow the servos to run |
| 96 | +//#define cVoltagePin 7 // Use our Analog pin jumper here... |
| 97 | +//#define CVADR1 1000 // VD Resistor 1 - reduced as only need ratio... 20K and 4.66K |
| 98 | +//#define CVADR2 233 // VD Resistor 2 |
| 99 | +#define cTurnOffVol 1000 // 10v |
| 100 | +#define cTurnOnVol 1100 // 11V - optional part to say if voltage goes back up, turn it back on... |
| 101 | + |
| 102 | +//==================================================================== |
| 103 | +#define DEFAULT_GAIT_SPEED 50 // Default gait speed - Will depend on what Servos you are using... |
| 104 | +#define DEFAULT_SLOW_GAIT 50 // Had a couple different speeds... |
| 105 | + |
| 106 | +//==================================================================== |
| 107 | + |
| 108 | + |
| 109 | +//-------------------------------------------------------------------- |
| 110 | +// Define which pins(sevo IDS go with which joint |
| 111 | + |
| 112 | +#define cRRCoxaPin 8 //Rear Right leg Hip Horizontal |
| 113 | +#define cRRFemurPin 10 //Rear Right leg Hip Vertical |
| 114 | +#define cRRTibiaPin 12 //Rear Right leg Knee |
| 115 | + |
| 116 | +#define cRFCoxaPin 2 //Front Right leg Hip Horizontal |
| 117 | +#define cRFFemurPin 4 //Front Right leg Hip Vertical |
| 118 | +#define cRFTibiaPin 6 //Front Right leg Knee |
| 119 | + |
| 120 | +#define cLRCoxaPin 7 //Rear Left leg Hip Horizontal |
| 121 | +#define cLRFemurPin 9 //Rear Left leg Hip Vertical |
| 122 | +#define cLRTibiaPin 11 //Rear Left leg Knee |
| 123 | + |
| 124 | +#define cLFCoxaPin 1 //Front Left leg Hip Horizontal |
| 125 | +#define cLFFemurPin 3 //Front Left leg Hip Vertical |
| 126 | +#define cLFTibiaPin 5 //Front Left leg Knee |
| 127 | + |
| 128 | + |
| 129 | +//-------------------------------------------------------------------- |
| 130 | +//[MIN/MAX ANGLES] - Warning - remember that some servos direction is |
| 131 | +// inverted in code after we do the conversions. So the Right legs need |
| 132 | +// to have their Min/Max values negated from what is seen on the actual robot |
| 133 | +// servo positions... |
| 134 | +//1:224(-843) 797(834) |
| 135 | +//3:159(-1034) 862(1025) |
| 136 | +//5:277(-688) 864(1031) |
| 137 | +//7:223(-846) 798(837) |
| 138 | +//9:160(-1031) 858(1013) |
| 139 | +//11:283(-670) 863(1028) |
| 140 | +//2:220(-855) 797(834) |
| 141 | +//4:163(-1022) 863(1028) |
| 142 | +//6:158(-1037) 747(688) |
| 143 | +//8:220(-855) 801(846) |
| 144 | +//10:255(-752) 861(1022) |
| 145 | +//12:125(-1133) 746(685) |
| 146 | +#define cRRCoxaMin1 -750 |
| 147 | +#define cRRCoxaMax1 750 |
| 148 | +#define cRRFemurMin1 -1000 |
| 149 | +#define cRRFemurMax1 1000 |
| 150 | +#define cRRTibiaMin1 -1020 |
| 151 | +#define cRRTibiaMax1 680 |
| 152 | + |
| 153 | +#define cRFCoxaMin1 -750 //Mechanical limits of the Right Front Leg, decimals = 1 |
| 154 | +#define cRFCoxaMax1 750 |
| 155 | +#define cRFFemurMin1 -1000 |
| 156 | +#define cRFFemurMax1 1000 |
| 157 | +#define cRFTibiaMin1 -1020 |
| 158 | +#define cRFTibiaMax1 680 |
| 159 | + |
| 160 | +#define cLRCoxaMin1 -750 //Mechanical limits of the Left Rear Leg, decimals = 1 |
| 161 | +#define cLRCoxaMax1 750 |
| 162 | +#define cLRFemurMin1 -1000 |
| 163 | +#define cLRFemurMax1 1000 |
| 164 | +#define cLRTibiaMin1 -1020 |
| 165 | +#define cLRTibiaMax1 680 |
| 166 | + |
| 167 | +#define cLFCoxaMin1 -750 //Mechanical limits of the Left Front Leg, decimals = 1 |
| 168 | +#define cLFCoxaMax1 750 |
| 169 | +#define cLFFemurMin1 -1000 |
| 170 | +#define cLFFemurMax1 1000 |
| 171 | +#define cLFTibiaMin1 -1020 |
| 172 | +#define cLFTibiaMax1 680 |
| 173 | + |
| 174 | +//-------------------------------------------------------------------- |
| 175 | +//[Joint offsets] |
| 176 | +// This allows us to calibrate servos to some fixed position, and then adjust them by moving theim |
| 177 | +// one or more servo horn clicks. This requires us to adjust the value for those servos by 15 degrees |
| 178 | +// per click. This is used with the T-Hex 4DOF legs |
| 179 | +//First calibrate the servos in the 0 deg position using the SSC-32 reg offsets, then: |
| 180 | +//-------------------------------------------------------------------- |
| 181 | +//[LEG DIMENSIONS] |
| 182 | +//Universal dimensions for each leg in mm |
| 183 | +#define cXXCoxaLength 52 // PhantomX leg dimensions. |
| 184 | +#define cXXFemurLength 65 |
| 185 | +#define cXXTibiaLength 133 |
| 186 | + |
| 187 | +#define cRRCoxaLength cXXCoxaLength //Right Rear leg |
| 188 | +#define cRRFemurLength cXXFemurLength |
| 189 | +#define cRRTibiaLength cXXTibiaLength |
| 190 | + |
| 191 | +#define cRFCoxaLength cXXCoxaLength //Rigth front leg |
| 192 | +#define cRFFemurLength cXXFemurLength |
| 193 | +#define cRFTibiaLength cXXTibiaLength |
| 194 | + |
| 195 | +#define cLRCoxaLength cXXCoxaLength //Left Rear leg |
| 196 | +#define cLRFemurLength cXXFemurLength |
| 197 | +#define cLRTibiaLength cXXTibiaLength |
| 198 | + |
| 199 | +#define cLFCoxaLength cXXCoxaLength //Left front leg |
| 200 | +#define cLFFemurLength cXXFemurLength |
| 201 | +#define cLFTibiaLength cXXTibiaLength |
| 202 | + |
| 203 | +//-------------------------------------------------------------------- |
| 204 | +//[BODY DIMENSIONS] |
| 205 | +#define cRRCoxaAngle1 -450 //Default Coxa setup angle, decimals = 1 |
| 206 | +#define cRFCoxaAngle1 450 //Default Coxa setup angle, decimals = 1 |
| 207 | +#define cLRCoxaAngle1 -450 //Default Coxa setup angle, decimals = 1 |
| 208 | +#define cLFCoxaAngle1 450 //Default Coxa setup angle, decimals = 1 |
| 209 | + |
| 210 | +#define X_COXA 65 // MM between front and back legs /2 |
| 211 | +#define Y_COXA 65 // MM between front/back legs /2 |
| 212 | + |
| 213 | +#define cRROffsetX -X_COXA //Distance X from center of the body to the Right Rear coxa |
| 214 | +#define cRROffsetZ Y_COXA //Distance Z from center of the body to the Right Rear coxa |
| 215 | + |
| 216 | +#define cRFOffsetX -X_COXA //Distance X from center of the body to the Right Front coxa |
| 217 | +#define cRFOffsetZ -Y_COXA //Distance Z from center of the body to the Right Front coxa |
| 218 | + |
| 219 | +#define cLROffsetX X_COXA //Distance X from center of the body to the Left Rear coxa |
| 220 | +#define cLROffsetZ Y_COXA //Distance Z from center of the body to the Left Rear coxa |
| 221 | + |
| 222 | +#define cLFOffsetX X_COXA //Distance X from center of the body to the Left Front coxa |
| 223 | +#define cLFOffsetZ -Y_COXA //Distance Z from center of the body to the Left Front coxa |
| 224 | + |
| 225 | +//-------------------------------------------------------------------- |
| 226 | +//[START POSITIONS FEET] |
| 227 | +#define cHexInitXZ 150 |
| 228 | +#define CHexInitXZCos60 130 //92 // COS(60) = .866 |
| 229 | +#define CHexInitXZSin60 75 // 92 // sin(60) = .5 |
| 230 | +#define CHexInitY 25 //30 |
| 231 | + |
| 232 | +// Lets try some multi leg positions depending on height settings. |
| 233 | +#define DYNAMIC_INIT_XZ |
| 234 | +#define CNT_HEX_INITS 3 |
| 235 | +#define MAX_BODY_Y 150 |
| 236 | + |
| 237 | +// For Inits we may want to tell system actual angles we are initiing servos to... |
| 238 | +// In some cases like some quads may not want legs straight out... |
| 239 | +#define cRRInitCoxaAngle1 -300 //Default Coxa setup angle, decimals = 1 |
| 240 | +#define cRFInitCoxaAngle1 300 //Default Coxa setup angle, decimals = 1 |
| 241 | +#define cLRInitCoxaAngle1 -300 //Default Coxa setup angle, decimals = 1 |
| 242 | +#define cLFInitCoxaAngle1 300 //Default Coxa setup angle, decimals = 1 |
| 243 | + |
| 244 | + |
| 245 | +#ifdef DEFINE_HEX_GLOBALS |
| 246 | +const byte g_abHexIntXZ[] PROGMEM = {cHexInitXZ, 130, 110}; |
| 247 | +const byte g_abHexMaxBodyY[] PROGMEM = { 30, 60, MAX_BODY_Y}; |
| 248 | +#else |
| 249 | +extern const byte g_abHexIntXZ[] PROGMEM; |
| 250 | +extern const byte g_abHexMaxBodyY[] PROGMEM; |
| 251 | +#endif |
| 252 | + |
| 253 | +#define cRRInitPosX CHexInitXZCos60 //Start positions of the Right Rear leg |
| 254 | +#define cRRInitPosY CHexInitY |
| 255 | +#define cRRInitPosZ CHexInitXZSin60 |
| 256 | + |
| 257 | +#define cRFInitPosX CHexInitXZCos60 //Start positions of the Right Front leg |
| 258 | +#define cRFInitPosY CHexInitY |
| 259 | +#define cRFInitPosZ -CHexInitXZSin60 |
| 260 | + |
| 261 | +#define cLRInitPosX CHexInitXZCos60 //Start positions of the Left Rear leg |
| 262 | +#define cLRInitPosY CHexInitY |
| 263 | +#define cLRInitPosZ CHexInitXZSin60 |
| 264 | + |
| 265 | +#define cLFInitPosX CHexInitXZCos60 //Start positions of the Left Front leg |
| 266 | +#define cLFInitPosY CHexInitY |
| 267 | +#define cLFInitPosZ -CHexInitXZSin60 |
| 268 | +//-------------------------------------------------------------------- |
| 269 | +#endif // HEX_CFG_H |
| 270 | + |
0 commit comments