Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: Communication_Robot QEI iSerial mbed motion_control
Fork of dog_V3_2_testmotor by
main.cpp@13:218c22a620cc, 2015-07-24 (annotated)
- Committer:
- soulx
- Date:
- Fri Jul 24 21:15:52 2015 +0000
- Revision:
- 13:218c22a620cc
- Parent:
- 12:2564eac22e0a
- Child:
- 14:7fe99764b2d0
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
soulx | 0:2433ddae2772 | 1 | #include "mbed.h" |
soulx | 0:2433ddae2772 | 2 | #include "pin_config.h" |
soulx | 0:2433ddae2772 | 3 | |
soulx | 6:8d80c84e0c09 | 4 | #include "communication.h" |
soulx | 6:8d80c84e0c09 | 5 | #include "protocol.h" |
soulx | 11:336dd293daa1 | 6 | #include "iSerial.h" |
soulx | 6:8d80c84e0c09 | 7 | |
soulx | 10:53cb691e22bf | 8 | #include "motor_relay.h" |
soulx | 10:53cb691e22bf | 9 | #include "motion_control.h" |
soulx | 10:53cb691e22bf | 10 | |
soulx | 6:8d80c84e0c09 | 11 | //set frequancy unit in Hz |
soulx | 6:8d80c84e0c09 | 12 | #define F_UPDATE 10.0f |
soulx | 6:8d80c84e0c09 | 13 | #define TIMER_UPDATE 1.0f/F_UPDATE |
soulx | 6:8d80c84e0c09 | 14 | |
soulx | 6:8d80c84e0c09 | 15 | //counter not receive from station |
soulx | 6:8d80c84e0c09 | 16 | #define TIMEOUT_RESPONE_COMMAND 5 |
soulx | 10:53cb691e22bf | 17 | |
soulx | 10:53cb691e22bf | 18 | MOTION_CONTROL leg_left_upper(INA_L_U,INB_L_U,LIMIT_LU_U,LIMIT_LU_D,VR_LU); |
soulx | 10:53cb691e22bf | 19 | MOTION_CONTROL leg_left_lower(INA_L_L,INB_L_L,LIMIT_LL_U,LIMIT_LL_D,VR_LL); |
soulx | 10:53cb691e22bf | 20 | MOTION_CONTROL leg_right_upper(INA_R_U,INB_R_U,LIMIT_RU_U,LIMIT_RU_D,VR_RU); |
soulx | 10:53cb691e22bf | 21 | MOTION_CONTROL leg_right_lower(INA_R_L,INB_R_L,LIMIT_RL_U,LIMIT_RL_D,VR_RL); |
soulx | 10:53cb691e22bf | 22 | |
soulx | 0:2433ddae2772 | 23 | DigitalOut myled(LED1); |
soulx | 0:2433ddae2772 | 24 | DigitalIn mybutton(USER_BUTTON); |
soulx | 0:2433ddae2772 | 25 | |
soulx | 6:8d80c84e0c09 | 26 | //communication config |
soulx | 6:8d80c84e0c09 | 27 | //serial for debug |
soulx | 13:218c22a620cc | 28 | Serial pc(USBTX, USBRX); |
soulx | 6:8d80c84e0c09 | 29 | //serial for xbee |
soulx | 6:8d80c84e0c09 | 30 | COMMUNICATION pan_a(TX_XBEE, RX_XBEE,115200,1000,1000); // tx, rx |
soulx | 0:2433ddae2772 | 31 | |
soulx | 11:336dd293daa1 | 32 | //Fuction prototye |
soulx | 11:336dd293daa1 | 33 | void getCommand(); |
soulx | 11:336dd293daa1 | 34 | // init function |
soulx | 11:336dd293daa1 | 35 | void calibration(); |
soulx | 11:336dd293daa1 | 36 | void test_position(); |
soulx | 12:2564eac22e0a | 37 | void test_status(); |
soulx | 12:2564eac22e0a | 38 | void test_limit(); |
soulx | 12:2564eac22e0a | 39 | void test_motor(); |
soulx | 0:2433ddae2772 | 40 | |
soulx | 12:2564eac22e0a | 41 | void routine(); |
soulx | 12:2564eac22e0a | 42 | |
soulx | 13:218c22a620cc | 43 | void serial_control(); |
soulx | 13:218c22a620cc | 44 | |
soulx | 12:2564eac22e0a | 45 | void management(ANDANTE_PROTOCOL_PACKET *packet); |
soulx | 0:2433ddae2772 | 46 | |
soulx | 11:336dd293daa1 | 47 | void copy_data(ANDANTE_PROTOCOL_PACKET *scr, ANDANTE_PROTOCOL_PACKET *dst); |
soulx | 0:2433ddae2772 | 48 | |
soulx | 6:8d80c84e0c09 | 49 | |
soulx | 6:8d80c84e0c09 | 50 | //set foreground |
soulx | 6:8d80c84e0c09 | 51 | Ticker Update_command; |
soulx | 6:8d80c84e0c09 | 52 | |
soulx | 11:336dd293daa1 | 53 | Timer t; |
soulx | 11:336dd293daa1 | 54 | |
soulx | 12:2564eac22e0a | 55 | //struct |
soulx | 12:2564eac22e0a | 56 | struct PARAM_WRITE { |
soulx | 12:2564eac22e0a | 57 | uint16_t left_up; |
soulx | 12:2564eac22e0a | 58 | uint16_t left_down; |
soulx | 12:2564eac22e0a | 59 | uint16_t right_up; |
soulx | 12:2564eac22e0a | 60 | uint16_t right_down; |
soulx | 12:2564eac22e0a | 61 | }; |
soulx | 12:2564eac22e0a | 62 | |
soulx | 11:336dd293daa1 | 63 | //variable |
soulx | 12:2564eac22e0a | 64 | //volatile ANDANTE_PROTOCOL_PACKET *param; |
soulx | 11:336dd293daa1 | 65 | volatile uint8_t status=0; |
soulx | 12:2564eac22e0a | 66 | //volatile PARAM_WRITE buff; |
soulx | 12:2564eac22e0a | 67 | PARAM_WRITE buff; |
soulx | 6:8d80c84e0c09 | 68 | |
soulx | 13:218c22a620cc | 69 | int serial_data; |
soulx | 13:218c22a620cc | 70 | |
soulx | 0:2433ddae2772 | 71 | //Main function |
soulx | 0:2433ddae2772 | 72 | int main() |
soulx | 0:2433ddae2772 | 73 | { |
soulx | 12:2564eac22e0a | 74 | //int state=0; |
soulx | 12:2564eac22e0a | 75 | |
soulx | 11:336dd293daa1 | 76 | pc.baud(115200); |
soulx | 11:336dd293daa1 | 77 | pc.printf("Welcome to DOGWHEELSCHAIR\n"); |
soulx | 12:2564eac22e0a | 78 | |
soulx | 12:2564eac22e0a | 79 | buff.left_up = 0; |
soulx | 12:2564eac22e0a | 80 | buff.right_up =0; |
soulx | 12:2564eac22e0a | 81 | buff.left_down = 64; |
soulx | 12:2564eac22e0a | 82 | buff.right_down = 64; |
soulx | 12:2564eac22e0a | 83 | |
soulx | 11:336dd293daa1 | 84 | if(mybutton == 0) { |
soulx | 11:336dd293daa1 | 85 | calibration(); |
soulx | 11:336dd293daa1 | 86 | } else { |
soulx | 11:336dd293daa1 | 87 | pc.printf("Lock position Min-Max..."); |
soulx | 13:218c22a620cc | 88 | leg_left_upper.SetMaxPosition(63787); |
soulx | 13:218c22a620cc | 89 | leg_left_upper.SetMinPosition(28653); |
soulx | 11:336dd293daa1 | 90 | |
soulx | 13:218c22a620cc | 91 | leg_left_lower.SetMaxPosition(57609); |
soulx | 13:218c22a620cc | 92 | leg_left_lower.SetMinPosition(17856); |
soulx | 11:336dd293daa1 | 93 | |
soulx | 13:218c22a620cc | 94 | leg_right_upper.SetMaxPosition(52094); |
soulx | 13:218c22a620cc | 95 | leg_right_upper.SetMinPosition(18928); |
soulx | 11:336dd293daa1 | 96 | |
soulx | 13:218c22a620cc | 97 | leg_right_lower.SetMaxPosition(54383); |
soulx | 13:218c22a620cc | 98 | leg_right_lower.SetMinPosition(8784); |
soulx | 11:336dd293daa1 | 99 | pc.printf("pass\n"); |
soulx | 11:336dd293daa1 | 100 | } |
soulx | 11:336dd293daa1 | 101 | |
soulx | 11:336dd293daa1 | 102 | Update_command.attach(&getCommand,TIMER_UPDATE); |
soulx | 11:336dd293daa1 | 103 | |
soulx | 13:218c22a620cc | 104 | serial_control(); |
soulx | 13:218c22a620cc | 105 | //test_motor(); |
soulx | 13:218c22a620cc | 106 | //test_limit(); |
soulx | 12:2564eac22e0a | 107 | test_status(); |
soulx | 12:2564eac22e0a | 108 | routine(); |
soulx | 11:336dd293daa1 | 109 | } |
soulx | 11:336dd293daa1 | 110 | |
soulx | 11:336dd293daa1 | 111 | void getCommand() |
soulx | 11:336dd293daa1 | 112 | { |
soulx | 11:336dd293daa1 | 113 | static uint8_t count =0; |
soulx | 11:336dd293daa1 | 114 | |
soulx | 11:336dd293daa1 | 115 | ANDANTE_PROTOCOL_PACKET packet; |
soulx | 11:336dd293daa1 | 116 | |
soulx | 11:336dd293daa1 | 117 | uint8_t status = pan_a.receiveCommunicatePacket(&packet); |
soulx | 11:336dd293daa1 | 118 | myled=0; |
soulx | 11:336dd293daa1 | 119 | |
soulx | 11:336dd293daa1 | 120 | if(status == ANDANTE_ERRBIT_NONE) { |
soulx | 11:336dd293daa1 | 121 | if(count >2 && count <10) { |
soulx | 11:336dd293daa1 | 122 | count--; |
soulx | 11:336dd293daa1 | 123 | } else { |
soulx | 11:336dd293daa1 | 124 | count=0; |
soulx | 5:f07cbb5a86c3 | 125 | } |
soulx | 11:336dd293daa1 | 126 | |
soulx | 11:336dd293daa1 | 127 | |
soulx | 12:2564eac22e0a | 128 | //pan_a.sendCommunicatePacket(&packet); |
soulx | 11:336dd293daa1 | 129 | |
soulx | 11:336dd293daa1 | 130 | //update command |
soulx | 11:336dd293daa1 | 131 | //setControl(&packet); |
soulx | 11:336dd293daa1 | 132 | |
soulx | 12:2564eac22e0a | 133 | |
soulx | 11:336dd293daa1 | 134 | } else if(status == ANDANTE_ERRBIT_READ_TIMEOUT) { |
soulx | 11:336dd293daa1 | 135 | count++; |
soulx | 11:336dd293daa1 | 136 | } |
soulx | 5:f07cbb5a86c3 | 137 | |
soulx | 11:336dd293daa1 | 138 | if(count >= TIMEOUT_RESPONE_COMMAND) { |
soulx | 11:336dd293daa1 | 139 | //stop robot |
soulx | 11:336dd293daa1 | 140 | count++; |
soulx | 11:336dd293daa1 | 141 | myled=1; |
soulx | 11:336dd293daa1 | 142 | // setSpeedControl(0.0); |
soulx | 11:336dd293daa1 | 143 | } |
soulx | 11:336dd293daa1 | 144 | } |
soulx | 0:2433ddae2772 | 145 | |
soulx | 11:336dd293daa1 | 146 | void calibration() |
soulx | 11:336dd293daa1 | 147 | { |
soulx | 11:336dd293daa1 | 148 | //calibration |
soulx | 11:336dd293daa1 | 149 | pc.printf("Calibration [START]\n"); |
soulx | 11:336dd293daa1 | 150 | leg_left_upper.calibration(); |
soulx | 11:336dd293daa1 | 151 | pc.printf("Left_UPPER\n"); |
soulx | 11:336dd293daa1 | 152 | pc.printf("max_position = %d\n",leg_left_upper.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 153 | pc.printf("min_position = %d\n",leg_left_upper.GetMinPosition()); |
soulx | 11:336dd293daa1 | 154 | leg_left_lower.calibration(); |
soulx | 11:336dd293daa1 | 155 | pc.printf("Left_Lower\n"); |
soulx | 11:336dd293daa1 | 156 | pc.printf("max_position = %d\n",leg_left_lower.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 157 | pc.printf("min_position = %d\n",leg_left_lower.GetMinPosition()); |
soulx | 11:336dd293daa1 | 158 | leg_right_upper.calibration(); |
soulx | 11:336dd293daa1 | 159 | pc.printf("right_UPPER\n"); |
soulx | 11:336dd293daa1 | 160 | pc.printf("max_position = %d\n",leg_right_upper.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 161 | pc.printf("min_position = %d\n",leg_right_upper.GetMinPosition()); |
soulx | 11:336dd293daa1 | 162 | leg_right_lower.calibration(); |
soulx | 11:336dd293daa1 | 163 | pc.printf("right_Lower\n"); |
soulx | 11:336dd293daa1 | 164 | pc.printf("max_position = %d\n",leg_right_lower.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 165 | pc.printf("min_position = %d\n",leg_right_lower.GetMinPosition()); |
soulx | 0:2433ddae2772 | 166 | |
soulx | 11:336dd293daa1 | 167 | pc.printf("Calibration [FINISH]\n"); |
soulx | 11:336dd293daa1 | 168 | pc.printf("RUN mode [START]\n"); |
soulx | 11:336dd293daa1 | 169 | wait(1); |
soulx | 11:336dd293daa1 | 170 | } |
soulx | 11:336dd293daa1 | 171 | |
soulx | 11:336dd293daa1 | 172 | void test_position() |
soulx | 11:336dd293daa1 | 173 | { |
soulx | 11:336dd293daa1 | 174 | uint8_t state; |
soulx | 11:336dd293daa1 | 175 | do { |
soulx | 10:53cb691e22bf | 176 | /* |
soulx | 10:53cb691e22bf | 177 | state=0; |
soulx | 10:53cb691e22bf | 178 | //leg_left_upper.position_control(500); |
soulx | 10:53cb691e22bf | 179 | if(leg_left_lower.position_control(500) ==2) |
soulx | 10:53cb691e22bf | 180 | state++; |
soulx | 10:53cb691e22bf | 181 | if(leg_right_upper.position_control(500) == 2) |
soulx | 10:53cb691e22bf | 182 | state++; |
soulx | 10:53cb691e22bf | 183 | if(leg_right_lower.position_control(500) == 2) |
soulx | 10:53cb691e22bf | 184 | state++; |
soulx | 10:53cb691e22bf | 185 | */ |
soulx | 10:53cb691e22bf | 186 | state = leg_left_upper.position_control(32); |
soulx | 10:53cb691e22bf | 187 | pc.printf("state_lu %d\n",state); |
soulx | 10:53cb691e22bf | 188 | state = leg_left_lower.position_control(32); |
soulx | 10:53cb691e22bf | 189 | pc.printf("state_ll %d\n",state); |
soulx | 10:53cb691e22bf | 190 | state = leg_right_upper.position_control(32); |
soulx | 10:53cb691e22bf | 191 | pc.printf("state_ru %d\n",state); |
soulx | 11:336dd293daa1 | 192 | state = leg_right_lower.position_control(32); |
soulx | 10:53cb691e22bf | 193 | pc.printf("state_rl %d\n",state); |
soulx | 10:53cb691e22bf | 194 | state=0; |
soulx | 11:336dd293daa1 | 195 | } while(state != 2); |
soulx | 10:53cb691e22bf | 196 | pc.printf("[Finish test]\n"); |
soulx | 12:2564eac22e0a | 197 | } |
soulx | 12:2564eac22e0a | 198 | |
soulx | 12:2564eac22e0a | 199 | void test_status() |
soulx | 13:218c22a620cc | 200 | { |
soulx | 12:2564eac22e0a | 201 | uint16_t state=0; |
soulx | 13:218c22a620cc | 202 | pc.printf("Test_status\n"); |
soulx | 12:2564eac22e0a | 203 | t.start(); |
soulx | 12:2564eac22e0a | 204 | while(1) { |
soulx | 12:2564eac22e0a | 205 | |
soulx | 13:218c22a620cc | 206 | if(pc.readable() == 1) { |
soulx | 13:218c22a620cc | 207 | serial_data = pc.getc(); |
soulx | 13:218c22a620cc | 208 | } |
soulx | 12:2564eac22e0a | 209 | |
soulx | 12:2564eac22e0a | 210 | if(t.read() > 10.0f) { |
soulx | 12:2564eac22e0a | 211 | t.reset(); |
soulx | 12:2564eac22e0a | 212 | if(status >3) { |
soulx | 12:2564eac22e0a | 213 | status =0; |
soulx | 12:2564eac22e0a | 214 | } else { |
soulx | 12:2564eac22e0a | 215 | status++; |
soulx | 12:2564eac22e0a | 216 | } |
soulx | 12:2564eac22e0a | 217 | } |
soulx | 12:2564eac22e0a | 218 | |
soulx | 12:2564eac22e0a | 219 | if(status == 0) { |
soulx | 12:2564eac22e0a | 220 | state =0; |
soulx | 12:2564eac22e0a | 221 | // sleep |
soulx | 12:2564eac22e0a | 222 | state += leg_left_upper.position_control(0); |
soulx | 12:2564eac22e0a | 223 | state += leg_right_upper.position_control(0); |
soulx | 12:2564eac22e0a | 224 | state += leg_left_lower.position_control(64); |
soulx | 12:2564eac22e0a | 225 | state += leg_right_lower.position_control(64); |
soulx | 12:2564eac22e0a | 226 | if(state == 8) { |
soulx | 12:2564eac22e0a | 227 | myled=1; |
soulx | 12:2564eac22e0a | 228 | } else { |
soulx | 12:2564eac22e0a | 229 | myled=0; |
soulx | 12:2564eac22e0a | 230 | } |
soulx | 12:2564eac22e0a | 231 | } else if(status == 1 || status ==3) { |
soulx | 12:2564eac22e0a | 232 | state =0; |
soulx | 12:2564eac22e0a | 233 | // sit |
soulx | 12:2564eac22e0a | 234 | state += leg_left_upper.position_control(64); |
soulx | 12:2564eac22e0a | 235 | state += leg_right_upper.position_control(64); |
soulx | 12:2564eac22e0a | 236 | state += leg_left_lower.position_control(64); |
soulx | 12:2564eac22e0a | 237 | state += leg_right_lower.position_control(64); |
soulx | 12:2564eac22e0a | 238 | if(state == 8) { |
soulx | 12:2564eac22e0a | 239 | myled=1; |
soulx | 12:2564eac22e0a | 240 | } else { |
soulx | 12:2564eac22e0a | 241 | myled=0; |
soulx | 12:2564eac22e0a | 242 | } |
soulx | 12:2564eac22e0a | 243 | } else if(status == 2) { |
soulx | 12:2564eac22e0a | 244 | state =0; |
soulx | 12:2564eac22e0a | 245 | // stand |
soulx | 12:2564eac22e0a | 246 | state += leg_left_upper.position_control(64); |
soulx | 12:2564eac22e0a | 247 | state += leg_right_upper.position_control(64); |
soulx | 12:2564eac22e0a | 248 | state += leg_left_lower.position_control(0); |
soulx | 12:2564eac22e0a | 249 | state += leg_right_lower.position_control(0); |
soulx | 12:2564eac22e0a | 250 | if(state == 8) { |
soulx | 12:2564eac22e0a | 251 | myled=1; |
soulx | 12:2564eac22e0a | 252 | } else { |
soulx | 12:2564eac22e0a | 253 | myled=0; |
soulx | 12:2564eac22e0a | 254 | } |
soulx | 12:2564eac22e0a | 255 | } |
soulx | 12:2564eac22e0a | 256 | } |
soulx | 12:2564eac22e0a | 257 | //t.stop(); |
soulx | 12:2564eac22e0a | 258 | } |
soulx | 12:2564eac22e0a | 259 | |
soulx | 12:2564eac22e0a | 260 | void management(ANDANTE_PROTOCOL_PACKET *packet) |
soulx | 12:2564eac22e0a | 261 | { |
soulx | 12:2564eac22e0a | 262 | switch(packet->instructionErrorId) { |
soulx | 12:2564eac22e0a | 263 | case 0x01: |
soulx | 12:2564eac22e0a | 264 | buff.left_up = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 265 | break; |
soulx | 12:2564eac22e0a | 266 | case 0x02: |
soulx | 12:2564eac22e0a | 267 | buff.left_down = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 268 | break; |
soulx | 12:2564eac22e0a | 269 | case 0x03: |
soulx | 12:2564eac22e0a | 270 | buff.right_up = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 271 | break; |
soulx | 12:2564eac22e0a | 272 | case 0x04: |
soulx | 12:2564eac22e0a | 273 | buff.right_down = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 274 | break; |
soulx | 12:2564eac22e0a | 275 | } |
soulx | 12:2564eac22e0a | 276 | } |
soulx | 12:2564eac22e0a | 277 | |
soulx | 12:2564eac22e0a | 278 | void routine() |
soulx | 12:2564eac22e0a | 279 | { |
soulx | 12:2564eac22e0a | 280 | uint8_t state=0; |
soulx | 12:2564eac22e0a | 281 | // PARAM_WRITE pos = buff; |
soulx | 12:2564eac22e0a | 282 | while(1) { |
soulx | 12:2564eac22e0a | 283 | state =0; |
soulx | 12:2564eac22e0a | 284 | // sit |
soulx | 12:2564eac22e0a | 285 | state += leg_left_upper.position_control(buff.left_up); |
soulx | 12:2564eac22e0a | 286 | state += leg_right_upper.position_control(buff.right_up); |
soulx | 12:2564eac22e0a | 287 | state += leg_left_lower.position_control(buff.left_down); |
soulx | 12:2564eac22e0a | 288 | state += leg_right_lower.position_control(buff.right_down); |
soulx | 12:2564eac22e0a | 289 | if(state == 8) { |
soulx | 12:2564eac22e0a | 290 | myled=1; |
soulx | 12:2564eac22e0a | 291 | } else { |
soulx | 12:2564eac22e0a | 292 | myled=0; |
soulx | 12:2564eac22e0a | 293 | } |
soulx | 12:2564eac22e0a | 294 | } |
soulx | 12:2564eac22e0a | 295 | } |
soulx | 12:2564eac22e0a | 296 | |
soulx | 12:2564eac22e0a | 297 | void test_limit() |
soulx | 12:2564eac22e0a | 298 | { |
soulx | 12:2564eac22e0a | 299 | pc.printf("TEST LIMIT ALL\n"); |
soulx | 13:218c22a620cc | 300 | t.start(); |
soulx | 12:2564eac22e0a | 301 | while(1) { |
soulx | 13:218c22a620cc | 302 | if(t.read() > 1.0f) { |
soulx | 13:218c22a620cc | 303 | t.reset(); |
soulx | 13:218c22a620cc | 304 | pc.printf("leftUP_limit_up = "); |
soulx | 13:218c22a620cc | 305 | if(leg_left_upper.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 306 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 307 | else |
soulx | 13:218c22a620cc | 308 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 309 | |
soulx | 13:218c22a620cc | 310 | pc.printf("leftUP_limit_down = "); |
soulx | 13:218c22a620cc | 311 | if(leg_left_upper.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 312 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 313 | else |
soulx | 13:218c22a620cc | 314 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 315 | |
soulx | 13:218c22a620cc | 316 | pc.printf("leftLOW_limit_up = "); |
soulx | 13:218c22a620cc | 317 | if(leg_left_lower.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 318 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 319 | else |
soulx | 13:218c22a620cc | 320 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 321 | |
soulx | 13:218c22a620cc | 322 | pc.printf("leftLow_limit_down = "); |
soulx | 13:218c22a620cc | 323 | if(leg_left_lower.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 324 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 325 | else |
soulx | 13:218c22a620cc | 326 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 327 | |
soulx | 12:2564eac22e0a | 328 | /////////////////////////////////////////////////////////////// |
soulx | 13:218c22a620cc | 329 | pc.printf("rightUP_limit_up = "); |
soulx | 13:218c22a620cc | 330 | if(leg_right_upper.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 331 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 332 | else |
soulx | 13:218c22a620cc | 333 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 334 | |
soulx | 13:218c22a620cc | 335 | pc.printf("rightUP_limit_down = "); |
soulx | 13:218c22a620cc | 336 | if(leg_right_upper.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 337 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 338 | else |
soulx | 13:218c22a620cc | 339 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 340 | |
soulx | 13:218c22a620cc | 341 | pc.printf("rightLOW_limit_up = "); |
soulx | 13:218c22a620cc | 342 | if(leg_right_lower.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 343 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 344 | else |
soulx | 13:218c22a620cc | 345 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 346 | |
soulx | 13:218c22a620cc | 347 | pc.printf("rightLow_limit_down = "); |
soulx | 13:218c22a620cc | 348 | if(leg_right_lower.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 349 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 350 | else |
soulx | 13:218c22a620cc | 351 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 352 | |
soulx | 13:218c22a620cc | 353 | pc.printf("\n\n"); |
soulx | 13:218c22a620cc | 354 | } |
soulx | 12:2564eac22e0a | 355 | } |
soulx | 12:2564eac22e0a | 356 | } |
soulx | 12:2564eac22e0a | 357 | |
soulx | 12:2564eac22e0a | 358 | void test_motor() |
soulx | 12:2564eac22e0a | 359 | { |
soulx | 12:2564eac22e0a | 360 | uint8_t state=0; |
soulx | 12:2564eac22e0a | 361 | |
soulx | 12:2564eac22e0a | 362 | pc.printf("TEST MOTOR DELAY\n"); |
soulx | 12:2564eac22e0a | 363 | t.start(); |
soulx | 12:2564eac22e0a | 364 | while(1) { |
soulx | 12:2564eac22e0a | 365 | if(t.read() > 1.5f) { |
soulx | 12:2564eac22e0a | 366 | t.reset(); |
soulx | 12:2564eac22e0a | 367 | if(state >1) { |
soulx | 12:2564eac22e0a | 368 | state =0; |
soulx | 12:2564eac22e0a | 369 | } else { |
soulx | 12:2564eac22e0a | 370 | state++; |
soulx | 12:2564eac22e0a | 371 | } |
soulx | 12:2564eac22e0a | 372 | } |
soulx | 12:2564eac22e0a | 373 | |
soulx | 12:2564eac22e0a | 374 | if(state ==0) { |
soulx | 12:2564eac22e0a | 375 | leg_left_upper.limit_motor(1); |
soulx | 12:2564eac22e0a | 376 | leg_right_upper.limit_motor(1); |
soulx | 12:2564eac22e0a | 377 | leg_left_lower.limit_motor(1); |
soulx | 12:2564eac22e0a | 378 | leg_right_lower.limit_motor(1); |
soulx | 12:2564eac22e0a | 379 | } else { |
soulx | 12:2564eac22e0a | 380 | { |
soulx | 12:2564eac22e0a | 381 | leg_left_upper.limit_motor(2); |
soulx | 12:2564eac22e0a | 382 | leg_right_upper.limit_motor(2); |
soulx | 12:2564eac22e0a | 383 | leg_left_lower.limit_motor(2); |
soulx | 12:2564eac22e0a | 384 | leg_right_lower.limit_motor(2); |
soulx | 12:2564eac22e0a | 385 | } |
soulx | 12:2564eac22e0a | 386 | } |
soulx | 12:2564eac22e0a | 387 | } |
soulx | 13:218c22a620cc | 388 | } |
soulx | 13:218c22a620cc | 389 | |
soulx | 13:218c22a620cc | 390 | void serial_control() |
soulx | 13:218c22a620cc | 391 | { |
soulx | 13:218c22a620cc | 392 | |
soulx | 13:218c22a620cc | 393 | uint16_t left_up=0; |
soulx | 13:218c22a620cc | 394 | uint16_t left_down=0; |
soulx | 13:218c22a620cc | 395 | uint16_t right_up=0; |
soulx | 13:218c22a620cc | 396 | uint16_t right_down=0; |
soulx | 13:218c22a620cc | 397 | |
soulx | 13:218c22a620cc | 398 | uint16_t offset_ll=8700; |
soulx | 13:218c22a620cc | 399 | uint16_t offset_rl=7500; |
soulx | 13:218c22a620cc | 400 | |
soulx | 13:218c22a620cc | 401 | uint8_t state=0; |
soulx | 13:218c22a620cc | 402 | |
soulx | 13:218c22a620cc | 403 | t.start(); |
soulx | 13:218c22a620cc | 404 | |
soulx | 13:218c22a620cc | 405 | while(1) { |
soulx | 13:218c22a620cc | 406 | if(pc.readable() == 1) { |
soulx | 13:218c22a620cc | 407 | serial_data = pc.getc(); |
soulx | 13:218c22a620cc | 408 | } |
soulx | 13:218c22a620cc | 409 | |
soulx | 13:218c22a620cc | 410 | switch(serial_data) { |
soulx | 13:218c22a620cc | 411 | case 'q': |
soulx | 13:218c22a620cc | 412 | if(left_up >=64) { |
soulx | 13:218c22a620cc | 413 | left_up= 63; |
soulx | 13:218c22a620cc | 414 | } else { |
soulx | 13:218c22a620cc | 415 | left_up++; |
soulx | 13:218c22a620cc | 416 | } |
soulx | 13:218c22a620cc | 417 | // serial_data=0; |
soulx | 13:218c22a620cc | 418 | break; |
soulx | 13:218c22a620cc | 419 | |
soulx | 13:218c22a620cc | 420 | case 'a': |
soulx | 13:218c22a620cc | 421 | if(left_up >=64 || left_up <=0) { |
soulx | 13:218c22a620cc | 422 | left_up= 0; |
soulx | 13:218c22a620cc | 423 | } else { |
soulx | 13:218c22a620cc | 424 | left_up--; |
soulx | 13:218c22a620cc | 425 | } |
soulx | 13:218c22a620cc | 426 | // serial_data=0; |
soulx | 13:218c22a620cc | 427 | break; |
soulx | 13:218c22a620cc | 428 | |
soulx | 13:218c22a620cc | 429 | case 'z': |
soulx | 13:218c22a620cc | 430 | if(left_up >=54) { |
soulx | 13:218c22a620cc | 431 | left_up= 63; |
soulx | 13:218c22a620cc | 432 | } else { |
soulx | 13:218c22a620cc | 433 | left_up+=10; |
soulx | 13:218c22a620cc | 434 | } |
soulx | 13:218c22a620cc | 435 | // serial_data=0; |
soulx | 13:218c22a620cc | 436 | break; |
soulx | 13:218c22a620cc | 437 | |
soulx | 13:218c22a620cc | 438 | case 'Z': |
soulx | 13:218c22a620cc | 439 | if(left_up >=54 || left_up <=10) { |
soulx | 13:218c22a620cc | 440 | left_up= 0; |
soulx | 13:218c22a620cc | 441 | } else { |
soulx | 13:218c22a620cc | 442 | left_up-=10; |
soulx | 13:218c22a620cc | 443 | } |
soulx | 13:218c22a620cc | 444 | // serial_data=0; |
soulx | 13:218c22a620cc | 445 | break; |
soulx | 13:218c22a620cc | 446 | |
soulx | 13:218c22a620cc | 447 | case 'w': |
soulx | 13:218c22a620cc | 448 | if(left_down >=64) { |
soulx | 13:218c22a620cc | 449 | left_down= 63; |
soulx | 13:218c22a620cc | 450 | } else { |
soulx | 13:218c22a620cc | 451 | left_down++; |
soulx | 13:218c22a620cc | 452 | } |
soulx | 13:218c22a620cc | 453 | // serial_data=0; |
soulx | 13:218c22a620cc | 454 | break; |
soulx | 13:218c22a620cc | 455 | |
soulx | 13:218c22a620cc | 456 | case 's': |
soulx | 13:218c22a620cc | 457 | if(left_down >=64 || left_down <=0) { |
soulx | 13:218c22a620cc | 458 | left_down= 0; |
soulx | 13:218c22a620cc | 459 | } else { |
soulx | 13:218c22a620cc | 460 | left_down--; |
soulx | 13:218c22a620cc | 461 | } |
soulx | 13:218c22a620cc | 462 | // serial_data=0; |
soulx | 13:218c22a620cc | 463 | break; |
soulx | 13:218c22a620cc | 464 | |
soulx | 13:218c22a620cc | 465 | case 'x': |
soulx | 13:218c22a620cc | 466 | if(left_down >=54) { |
soulx | 13:218c22a620cc | 467 | left_down= 63; |
soulx | 13:218c22a620cc | 468 | } else { |
soulx | 13:218c22a620cc | 469 | left_down+=10; |
soulx | 13:218c22a620cc | 470 | } |
soulx | 13:218c22a620cc | 471 | // serial_data=0; |
soulx | 13:218c22a620cc | 472 | break; |
soulx | 13:218c22a620cc | 473 | |
soulx | 13:218c22a620cc | 474 | case 'X': |
soulx | 13:218c22a620cc | 475 | if(left_down >=54 || left_down <=10) { |
soulx | 13:218c22a620cc | 476 | left_down= 0; |
soulx | 13:218c22a620cc | 477 | } else { |
soulx | 13:218c22a620cc | 478 | left_down-=10; |
soulx | 13:218c22a620cc | 479 | } |
soulx | 13:218c22a620cc | 480 | //serial_data=0; |
soulx | 13:218c22a620cc | 481 | break; |
soulx | 13:218c22a620cc | 482 | |
soulx | 13:218c22a620cc | 483 | |
soulx | 13:218c22a620cc | 484 | case 'e': |
soulx | 13:218c22a620cc | 485 | if(right_up >=64) { |
soulx | 13:218c22a620cc | 486 | right_up= 63; |
soulx | 13:218c22a620cc | 487 | } else { |
soulx | 13:218c22a620cc | 488 | right_up++; |
soulx | 13:218c22a620cc | 489 | } |
soulx | 13:218c22a620cc | 490 | // serial_data=0; |
soulx | 13:218c22a620cc | 491 | break; |
soulx | 13:218c22a620cc | 492 | |
soulx | 13:218c22a620cc | 493 | case 'd': |
soulx | 13:218c22a620cc | 494 | if(right_up >=64 || right_up <=0) { |
soulx | 13:218c22a620cc | 495 | right_up= 0; |
soulx | 13:218c22a620cc | 496 | } else { |
soulx | 13:218c22a620cc | 497 | right_up--; |
soulx | 13:218c22a620cc | 498 | } |
soulx | 13:218c22a620cc | 499 | // serial_data=0; |
soulx | 13:218c22a620cc | 500 | break; |
soulx | 13:218c22a620cc | 501 | |
soulx | 13:218c22a620cc | 502 | case 'c': |
soulx | 13:218c22a620cc | 503 | if(right_up >=54) { |
soulx | 13:218c22a620cc | 504 | right_up= 63; |
soulx | 13:218c22a620cc | 505 | } else { |
soulx | 13:218c22a620cc | 506 | right_up+=10; |
soulx | 13:218c22a620cc | 507 | } |
soulx | 13:218c22a620cc | 508 | // serial_data=0; |
soulx | 13:218c22a620cc | 509 | break; |
soulx | 13:218c22a620cc | 510 | |
soulx | 13:218c22a620cc | 511 | case 'C': |
soulx | 13:218c22a620cc | 512 | if(right_up >=54 || right_up <=10) { |
soulx | 13:218c22a620cc | 513 | right_up= 0; |
soulx | 13:218c22a620cc | 514 | } else { |
soulx | 13:218c22a620cc | 515 | right_up-=10; |
soulx | 13:218c22a620cc | 516 | } |
soulx | 13:218c22a620cc | 517 | // serial_data=0; |
soulx | 13:218c22a620cc | 518 | break; |
soulx | 13:218c22a620cc | 519 | |
soulx | 13:218c22a620cc | 520 | |
soulx | 13:218c22a620cc | 521 | |
soulx | 13:218c22a620cc | 522 | |
soulx | 13:218c22a620cc | 523 | case 'r': |
soulx | 13:218c22a620cc | 524 | if(right_down >=64) { |
soulx | 13:218c22a620cc | 525 | right_down= 63; |
soulx | 13:218c22a620cc | 526 | } else { |
soulx | 13:218c22a620cc | 527 | right_down++; |
soulx | 13:218c22a620cc | 528 | } |
soulx | 13:218c22a620cc | 529 | |
soulx | 13:218c22a620cc | 530 | break; |
soulx | 13:218c22a620cc | 531 | |
soulx | 13:218c22a620cc | 532 | case 'f': |
soulx | 13:218c22a620cc | 533 | if(right_down >=64 || right_down <=0) { |
soulx | 13:218c22a620cc | 534 | right_down= 0; |
soulx | 13:218c22a620cc | 535 | } else { |
soulx | 13:218c22a620cc | 536 | right_down--; |
soulx | 13:218c22a620cc | 537 | } |
soulx | 13:218c22a620cc | 538 | |
soulx | 13:218c22a620cc | 539 | break; |
soulx | 13:218c22a620cc | 540 | |
soulx | 13:218c22a620cc | 541 | case 'v': |
soulx | 13:218c22a620cc | 542 | if(right_down >=54) { |
soulx | 13:218c22a620cc | 543 | right_down= 63; |
soulx | 13:218c22a620cc | 544 | } else { |
soulx | 13:218c22a620cc | 545 | right_down+=10; |
soulx | 13:218c22a620cc | 546 | } |
soulx | 13:218c22a620cc | 547 | |
soulx | 13:218c22a620cc | 548 | break; |
soulx | 13:218c22a620cc | 549 | |
soulx | 13:218c22a620cc | 550 | case 'V': |
soulx | 13:218c22a620cc | 551 | if(right_down >=54 || right_down <=10) { |
soulx | 13:218c22a620cc | 552 | right_down= 0; |
soulx | 13:218c22a620cc | 553 | } else { |
soulx | 13:218c22a620cc | 554 | right_down-=10; |
soulx | 13:218c22a620cc | 555 | } |
soulx | 13:218c22a620cc | 556 | |
soulx | 13:218c22a620cc | 557 | break; |
soulx | 13:218c22a620cc | 558 | |
soulx | 13:218c22a620cc | 559 | case 'p': |
soulx | 13:218c22a620cc | 560 | test_status(); |
soulx | 13:218c22a620cc | 561 | break; |
soulx | 13:218c22a620cc | 562 | |
soulx | 13:218c22a620cc | 563 | case 'y': |
soulx | 13:218c22a620cc | 564 | if(offset_ll > 30000) { |
soulx | 13:218c22a620cc | 565 | offset_ll =30000; |
soulx | 13:218c22a620cc | 566 | } else { |
soulx | 13:218c22a620cc | 567 | |
soulx | 13:218c22a620cc | 568 | offset_ll+=100; |
soulx | 13:218c22a620cc | 569 | } |
soulx | 13:218c22a620cc | 570 | leg_left_lower.SetOffset(offset_ll); |
soulx | 13:218c22a620cc | 571 | break; |
soulx | 13:218c22a620cc | 572 | |
soulx | 13:218c22a620cc | 573 | case 'h': |
soulx | 13:218c22a620cc | 574 | if(offset_ll <= 100) { |
soulx | 13:218c22a620cc | 575 | offset_ll =0; |
soulx | 13:218c22a620cc | 576 | } else { |
soulx | 13:218c22a620cc | 577 | |
soulx | 13:218c22a620cc | 578 | offset_ll-=100; |
soulx | 13:218c22a620cc | 579 | } |
soulx | 13:218c22a620cc | 580 | leg_left_lower.SetOffset(offset_ll); |
soulx | 13:218c22a620cc | 581 | break; |
soulx | 13:218c22a620cc | 582 | |
soulx | 13:218c22a620cc | 583 | case 'u': |
soulx | 13:218c22a620cc | 584 | if(offset_rl > 30000) { |
soulx | 13:218c22a620cc | 585 | offset_rl =30000; |
soulx | 13:218c22a620cc | 586 | } else { |
soulx | 13:218c22a620cc | 587 | |
soulx | 13:218c22a620cc | 588 | offset_rl+=100; |
soulx | 13:218c22a620cc | 589 | } |
soulx | 13:218c22a620cc | 590 | leg_right_lower.SetOffset(offset_rl); |
soulx | 13:218c22a620cc | 591 | break; |
soulx | 13:218c22a620cc | 592 | |
soulx | 13:218c22a620cc | 593 | case 'j': |
soulx | 13:218c22a620cc | 594 | if(offset_rl <= 100) { |
soulx | 13:218c22a620cc | 595 | offset_rl =0; |
soulx | 13:218c22a620cc | 596 | } else { |
soulx | 13:218c22a620cc | 597 | |
soulx | 13:218c22a620cc | 598 | offset_rl-=100; |
soulx | 13:218c22a620cc | 599 | } |
soulx | 13:218c22a620cc | 600 | leg_right_lower.SetOffset(offset_rl); |
soulx | 13:218c22a620cc | 601 | break; |
soulx | 13:218c22a620cc | 602 | |
soulx | 13:218c22a620cc | 603 | case '0': |
soulx | 13:218c22a620cc | 604 | leg_left_lower.SetMode(0); |
soulx | 13:218c22a620cc | 605 | leg_right_lower.SetMode(0); |
soulx | 13:218c22a620cc | 606 | pc.printf("MODE 0:ON\n"); |
soulx | 13:218c22a620cc | 607 | break; |
soulx | 13:218c22a620cc | 608 | case '1': |
soulx | 13:218c22a620cc | 609 | leg_left_lower.SetMode(1); |
soulx | 13:218c22a620cc | 610 | leg_right_lower.SetMode(1); |
soulx | 13:218c22a620cc | 611 | pc.printf("MODE 1:ON\n"); |
soulx | 13:218c22a620cc | 612 | break; |
soulx | 13:218c22a620cc | 613 | case '2': |
soulx | 13:218c22a620cc | 614 | leg_left_lower.SetMode(2); |
soulx | 13:218c22a620cc | 615 | leg_right_lower.SetMode(2); |
soulx | 13:218c22a620cc | 616 | pc.printf("MODE 2:ON\n"); |
soulx | 13:218c22a620cc | 617 | break; |
soulx | 13:218c22a620cc | 618 | } |
soulx | 13:218c22a620cc | 619 | |
soulx | 13:218c22a620cc | 620 | if(t.read() > 1.0f) { |
soulx | 13:218c22a620cc | 621 | t.reset(); |
soulx | 13:218c22a620cc | 622 | pc.printf("left_up %d\n",left_up); |
soulx | 13:218c22a620cc | 623 | pc.printf("left_down %d\n",left_down); |
soulx | 13:218c22a620cc | 624 | pc.printf("right_up %d\n",right_up); |
soulx | 13:218c22a620cc | 625 | pc.printf("right_down %d\n",right_down); |
soulx | 13:218c22a620cc | 626 | pc.printf("offset_ll %d\n",offset_ll); |
soulx | 13:218c22a620cc | 627 | pc.printf("offset_rl %d\n",offset_rl); |
soulx | 13:218c22a620cc | 628 | pc.printf("\n"); |
soulx | 13:218c22a620cc | 629 | |
soulx | 13:218c22a620cc | 630 | } |
soulx | 13:218c22a620cc | 631 | serial_data=0; |
soulx | 13:218c22a620cc | 632 | state =0; |
soulx | 13:218c22a620cc | 633 | |
soulx | 13:218c22a620cc | 634 | state += leg_left_upper.position_control(left_up); |
soulx | 13:218c22a620cc | 635 | state += leg_right_upper.position_control(right_up); |
soulx | 13:218c22a620cc | 636 | state += leg_left_lower.position_control(left_down); |
soulx | 13:218c22a620cc | 637 | state += leg_right_lower.position_control(right_down); |
soulx | 13:218c22a620cc | 638 | if(state == 8) { |
soulx | 13:218c22a620cc | 639 | myled=1; |
soulx | 13:218c22a620cc | 640 | } else { |
soulx | 13:218c22a620cc | 641 | myled=0; |
soulx | 13:218c22a620cc | 642 | } |
soulx | 13:218c22a620cc | 643 | } |
soulx | 6:8d80c84e0c09 | 644 | } |