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@16:ec0cba3631bc, 2015-10-06 (annotated)
- Committer:
- soulx
- Date:
- Tue Oct 06 12:31:21 2015 +0000
- Revision:
- 16:ec0cba3631bc
- Parent:
- 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 | 14:7fe99764b2d0 | 11 | #include "QEI.h" |
soulx | 14:7fe99764b2d0 | 12 | |
soulx | 6:8d80c84e0c09 | 13 | //set frequancy unit in Hz |
soulx | 6:8d80c84e0c09 | 14 | #define F_UPDATE 10.0f |
soulx | 6:8d80c84e0c09 | 15 | #define TIMER_UPDATE 1.0f/F_UPDATE |
soulx | 6:8d80c84e0c09 | 16 | |
soulx | 6:8d80c84e0c09 | 17 | //counter not receive from station |
soulx | 6:8d80c84e0c09 | 18 | #define TIMEOUT_RESPONE_COMMAND 5 |
soulx | 10:53cb691e22bf | 19 | |
soulx | 14:7fe99764b2d0 | 20 | // |
soulx | 14:7fe99764b2d0 | 21 | #define PULSE_RESOLUTION 500 |
soulx | 14:7fe99764b2d0 | 22 | |
soulx | 16:ec0cba3631bc | 23 | //struct |
soulx | 16:ec0cba3631bc | 24 | struct PARAM_WRITE { |
soulx | 16:ec0cba3631bc | 25 | uint16_t left_up; |
soulx | 16:ec0cba3631bc | 26 | uint16_t left_down; |
soulx | 16:ec0cba3631bc | 27 | uint16_t right_up; |
soulx | 16:ec0cba3631bc | 28 | uint16_t right_down; |
soulx | 16:ec0cba3631bc | 29 | }; |
soulx | 16:ec0cba3631bc | 30 | |
soulx | 10:53cb691e22bf | 31 | MOTION_CONTROL leg_left_upper(INA_L_U,INB_L_U,LIMIT_LU_U,LIMIT_LU_D,VR_LU); |
soulx | 10:53cb691e22bf | 32 | MOTION_CONTROL leg_left_lower(INA_L_L,INB_L_L,LIMIT_LL_U,LIMIT_LL_D,VR_LL); |
soulx | 10:53cb691e22bf | 33 | MOTION_CONTROL leg_right_upper(INA_R_U,INB_R_U,LIMIT_RU_U,LIMIT_RU_D,VR_RU); |
soulx | 10:53cb691e22bf | 34 | MOTION_CONTROL leg_right_lower(INA_R_L,INB_R_L,LIMIT_RL_U,LIMIT_RL_D,VR_RL); |
soulx | 10:53cb691e22bf | 35 | |
soulx | 0:2433ddae2772 | 36 | DigitalOut myled(LED1); |
soulx | 0:2433ddae2772 | 37 | DigitalIn mybutton(USER_BUTTON); |
soulx | 0:2433ddae2772 | 38 | |
soulx | 6:8d80c84e0c09 | 39 | //communication config |
soulx | 6:8d80c84e0c09 | 40 | //serial for debug |
soulx | 13:218c22a620cc | 41 | Serial pc(USBTX, USBRX); |
soulx | 6:8d80c84e0c09 | 42 | //serial for xbee |
soulx | 6:8d80c84e0c09 | 43 | COMMUNICATION pan_a(TX_XBEE, RX_XBEE,115200,1000,1000); // tx, rx |
soulx | 0:2433ddae2772 | 44 | |
soulx | 14:7fe99764b2d0 | 45 | QEI wheel (ENCODE_A, ENCODE_B, ENCODE_Z, PULSE_RESOLUTION); |
soulx | 14:7fe99764b2d0 | 46 | |
soulx | 11:336dd293daa1 | 47 | //Fuction prototye |
soulx | 11:336dd293daa1 | 48 | void getCommand(); |
soulx | 11:336dd293daa1 | 49 | // init function |
soulx | 11:336dd293daa1 | 50 | void calibration(); |
soulx | 11:336dd293daa1 | 51 | void test_position(); |
soulx | 12:2564eac22e0a | 52 | void test_status(); |
soulx | 16:ec0cba3631bc | 53 | void test_status2(PARAM_WRITE d1, PARAM_WRITE d2); |
soulx | 14:7fe99764b2d0 | 54 | void test_sleep(); |
soulx | 14:7fe99764b2d0 | 55 | void test_sit(); |
soulx | 16:ec0cba3631bc | 56 | void test_stand(PARAM_WRITE d1); |
soulx | 14:7fe99764b2d0 | 57 | |
soulx | 12:2564eac22e0a | 58 | void test_limit(); |
soulx | 12:2564eac22e0a | 59 | void test_motor(); |
soulx | 0:2433ddae2772 | 60 | |
soulx | 12:2564eac22e0a | 61 | void routine(); |
soulx | 12:2564eac22e0a | 62 | |
soulx | 13:218c22a620cc | 63 | void serial_control(); |
soulx | 13:218c22a620cc | 64 | |
soulx | 12:2564eac22e0a | 65 | void management(ANDANTE_PROTOCOL_PACKET *packet); |
soulx | 0:2433ddae2772 | 66 | |
soulx | 11:336dd293daa1 | 67 | void copy_data(ANDANTE_PROTOCOL_PACKET *scr, ANDANTE_PROTOCOL_PACKET *dst); |
soulx | 0:2433ddae2772 | 68 | |
soulx | 6:8d80c84e0c09 | 69 | |
soulx | 6:8d80c84e0c09 | 70 | //set foreground |
soulx | 6:8d80c84e0c09 | 71 | Ticker Update_command; |
soulx | 6:8d80c84e0c09 | 72 | |
soulx | 11:336dd293daa1 | 73 | Timer t; |
soulx | 11:336dd293daa1 | 74 | |
soulx | 16:ec0cba3631bc | 75 | |
soulx | 12:2564eac22e0a | 76 | |
soulx | 11:336dd293daa1 | 77 | //variable |
soulx | 12:2564eac22e0a | 78 | //volatile ANDANTE_PROTOCOL_PACKET *param; |
soulx | 11:336dd293daa1 | 79 | volatile uint8_t status=0; |
soulx | 12:2564eac22e0a | 80 | //volatile PARAM_WRITE buff; |
soulx | 16:ec0cba3631bc | 81 | PARAM_WRITE buff1,buff2; |
soulx | 6:8d80c84e0c09 | 82 | |
soulx | 13:218c22a620cc | 83 | int serial_data; |
soulx | 13:218c22a620cc | 84 | |
soulx | 0:2433ddae2772 | 85 | //Main function |
soulx | 0:2433ddae2772 | 86 | int main() |
soulx | 0:2433ddae2772 | 87 | { |
soulx | 12:2564eac22e0a | 88 | //int state=0; |
soulx | 12:2564eac22e0a | 89 | |
soulx | 11:336dd293daa1 | 90 | pc.baud(115200); |
soulx | 11:336dd293daa1 | 91 | pc.printf("Welcome to DOGWHEELSCHAIR\n"); |
soulx | 12:2564eac22e0a | 92 | |
soulx | 12:2564eac22e0a | 93 | |
soulx | 11:336dd293daa1 | 94 | if(mybutton == 0) { |
soulx | 11:336dd293daa1 | 95 | calibration(); |
soulx | 11:336dd293daa1 | 96 | } else { |
soulx | 11:336dd293daa1 | 97 | pc.printf("Lock position Min-Max..."); |
soulx | 14:7fe99764b2d0 | 98 | leg_left_upper.SetMaxPosition(62787); |
soulx | 14:7fe99764b2d0 | 99 | leg_left_upper.SetMinPosition(29353); |
soulx | 11:336dd293daa1 | 100 | |
soulx | 14:7fe99764b2d0 | 101 | leg_left_lower.SetMaxPosition(57000); |
soulx | 14:7fe99764b2d0 | 102 | leg_left_lower.SetMinPosition(8200); |
soulx | 11:336dd293daa1 | 103 | |
soulx | 14:7fe99764b2d0 | 104 | leg_right_upper.SetMaxPosition(43494); |
soulx | 14:7fe99764b2d0 | 105 | leg_right_upper.SetMinPosition(12028); |
soulx | 11:336dd293daa1 | 106 | |
soulx | 14:7fe99764b2d0 | 107 | leg_right_lower.SetMaxPosition(53383); |
soulx | 14:7fe99764b2d0 | 108 | leg_right_lower.SetMinPosition(12584); |
soulx | 11:336dd293daa1 | 109 | pc.printf("pass\n"); |
soulx | 11:336dd293daa1 | 110 | } |
soulx | 11:336dd293daa1 | 111 | |
soulx | 11:336dd293daa1 | 112 | Update_command.attach(&getCommand,TIMER_UPDATE); |
soulx | 11:336dd293daa1 | 113 | |
soulx | 13:218c22a620cc | 114 | serial_control(); |
soulx | 13:218c22a620cc | 115 | //test_motor(); |
soulx | 13:218c22a620cc | 116 | //test_limit(); |
soulx | 12:2564eac22e0a | 117 | test_status(); |
soulx | 12:2564eac22e0a | 118 | routine(); |
soulx | 11:336dd293daa1 | 119 | } |
soulx | 11:336dd293daa1 | 120 | |
soulx | 11:336dd293daa1 | 121 | void getCommand() |
soulx | 11:336dd293daa1 | 122 | { |
soulx | 11:336dd293daa1 | 123 | static uint8_t count =0; |
soulx | 11:336dd293daa1 | 124 | |
soulx | 11:336dd293daa1 | 125 | ANDANTE_PROTOCOL_PACKET packet; |
soulx | 11:336dd293daa1 | 126 | |
soulx | 11:336dd293daa1 | 127 | uint8_t status = pan_a.receiveCommunicatePacket(&packet); |
soulx | 11:336dd293daa1 | 128 | myled=0; |
soulx | 11:336dd293daa1 | 129 | |
soulx | 11:336dd293daa1 | 130 | if(status == ANDANTE_ERRBIT_NONE) { |
soulx | 11:336dd293daa1 | 131 | if(count >2 && count <10) { |
soulx | 11:336dd293daa1 | 132 | count--; |
soulx | 11:336dd293daa1 | 133 | } else { |
soulx | 11:336dd293daa1 | 134 | count=0; |
soulx | 5:f07cbb5a86c3 | 135 | } |
soulx | 11:336dd293daa1 | 136 | |
soulx | 11:336dd293daa1 | 137 | |
soulx | 12:2564eac22e0a | 138 | //pan_a.sendCommunicatePacket(&packet); |
soulx | 11:336dd293daa1 | 139 | |
soulx | 11:336dd293daa1 | 140 | //update command |
soulx | 11:336dd293daa1 | 141 | //setControl(&packet); |
soulx | 11:336dd293daa1 | 142 | |
soulx | 12:2564eac22e0a | 143 | |
soulx | 11:336dd293daa1 | 144 | } else if(status == ANDANTE_ERRBIT_READ_TIMEOUT) { |
soulx | 11:336dd293daa1 | 145 | count++; |
soulx | 11:336dd293daa1 | 146 | } |
soulx | 5:f07cbb5a86c3 | 147 | |
soulx | 11:336dd293daa1 | 148 | if(count >= TIMEOUT_RESPONE_COMMAND) { |
soulx | 11:336dd293daa1 | 149 | //stop robot |
soulx | 11:336dd293daa1 | 150 | count++; |
soulx | 11:336dd293daa1 | 151 | myled=1; |
soulx | 11:336dd293daa1 | 152 | // setSpeedControl(0.0); |
soulx | 11:336dd293daa1 | 153 | } |
soulx | 11:336dd293daa1 | 154 | } |
soulx | 0:2433ddae2772 | 155 | |
soulx | 11:336dd293daa1 | 156 | void calibration() |
soulx | 11:336dd293daa1 | 157 | { |
soulx | 11:336dd293daa1 | 158 | //calibration |
soulx | 11:336dd293daa1 | 159 | pc.printf("Calibration [START]\n"); |
soulx | 11:336dd293daa1 | 160 | leg_left_upper.calibration(); |
soulx | 11:336dd293daa1 | 161 | pc.printf("Left_UPPER\n"); |
soulx | 11:336dd293daa1 | 162 | pc.printf("max_position = %d\n",leg_left_upper.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 163 | pc.printf("min_position = %d\n",leg_left_upper.GetMinPosition()); |
soulx | 11:336dd293daa1 | 164 | leg_left_lower.calibration(); |
soulx | 11:336dd293daa1 | 165 | pc.printf("Left_Lower\n"); |
soulx | 11:336dd293daa1 | 166 | pc.printf("max_position = %d\n",leg_left_lower.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 167 | pc.printf("min_position = %d\n",leg_left_lower.GetMinPosition()); |
soulx | 11:336dd293daa1 | 168 | leg_right_upper.calibration(); |
soulx | 11:336dd293daa1 | 169 | pc.printf("right_UPPER\n"); |
soulx | 11:336dd293daa1 | 170 | pc.printf("max_position = %d\n",leg_right_upper.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 171 | pc.printf("min_position = %d\n",leg_right_upper.GetMinPosition()); |
soulx | 11:336dd293daa1 | 172 | leg_right_lower.calibration(); |
soulx | 11:336dd293daa1 | 173 | pc.printf("right_Lower\n"); |
soulx | 11:336dd293daa1 | 174 | pc.printf("max_position = %d\n",leg_right_lower.GetMaxPosition()); |
soulx | 11:336dd293daa1 | 175 | pc.printf("min_position = %d\n",leg_right_lower.GetMinPosition()); |
soulx | 0:2433ddae2772 | 176 | |
soulx | 11:336dd293daa1 | 177 | pc.printf("Calibration [FINISH]\n"); |
soulx | 11:336dd293daa1 | 178 | pc.printf("RUN mode [START]\n"); |
soulx | 11:336dd293daa1 | 179 | wait(1); |
soulx | 11:336dd293daa1 | 180 | } |
soulx | 11:336dd293daa1 | 181 | |
soulx | 11:336dd293daa1 | 182 | void test_position() |
soulx | 11:336dd293daa1 | 183 | { |
soulx | 11:336dd293daa1 | 184 | uint8_t state; |
soulx | 11:336dd293daa1 | 185 | do { |
soulx | 10:53cb691e22bf | 186 | /* |
soulx | 10:53cb691e22bf | 187 | state=0; |
soulx | 10:53cb691e22bf | 188 | //leg_left_upper.position_control(500); |
soulx | 10:53cb691e22bf | 189 | if(leg_left_lower.position_control(500) ==2) |
soulx | 10:53cb691e22bf | 190 | state++; |
soulx | 10:53cb691e22bf | 191 | if(leg_right_upper.position_control(500) == 2) |
soulx | 10:53cb691e22bf | 192 | state++; |
soulx | 10:53cb691e22bf | 193 | if(leg_right_lower.position_control(500) == 2) |
soulx | 10:53cb691e22bf | 194 | state++; |
soulx | 10:53cb691e22bf | 195 | */ |
soulx | 10:53cb691e22bf | 196 | state = leg_left_upper.position_control(32); |
soulx | 10:53cb691e22bf | 197 | pc.printf("state_lu %d\n",state); |
soulx | 10:53cb691e22bf | 198 | state = leg_left_lower.position_control(32); |
soulx | 10:53cb691e22bf | 199 | pc.printf("state_ll %d\n",state); |
soulx | 10:53cb691e22bf | 200 | state = leg_right_upper.position_control(32); |
soulx | 10:53cb691e22bf | 201 | pc.printf("state_ru %d\n",state); |
soulx | 11:336dd293daa1 | 202 | state = leg_right_lower.position_control(32); |
soulx | 10:53cb691e22bf | 203 | pc.printf("state_rl %d\n",state); |
soulx | 10:53cb691e22bf | 204 | state=0; |
soulx | 11:336dd293daa1 | 205 | } while(state != 2); |
soulx | 10:53cb691e22bf | 206 | pc.printf("[Finish test]\n"); |
soulx | 12:2564eac22e0a | 207 | } |
soulx | 12:2564eac22e0a | 208 | |
soulx | 12:2564eac22e0a | 209 | void test_status() |
soulx | 14:7fe99764b2d0 | 210 | { |
soulx | 12:2564eac22e0a | 211 | uint16_t state=0; |
soulx | 13:218c22a620cc | 212 | pc.printf("Test_status\n"); |
soulx | 12:2564eac22e0a | 213 | t.start(); |
soulx | 12:2564eac22e0a | 214 | while(1) { |
soulx | 12:2564eac22e0a | 215 | |
soulx | 13:218c22a620cc | 216 | if(pc.readable() == 1) { |
soulx | 13:218c22a620cc | 217 | serial_data = pc.getc(); |
soulx | 13:218c22a620cc | 218 | } |
soulx | 12:2564eac22e0a | 219 | |
soulx | 12:2564eac22e0a | 220 | if(t.read() > 10.0f) { |
soulx | 12:2564eac22e0a | 221 | t.reset(); |
soulx | 12:2564eac22e0a | 222 | if(status >3) { |
soulx | 12:2564eac22e0a | 223 | status =0; |
soulx | 12:2564eac22e0a | 224 | } else { |
soulx | 12:2564eac22e0a | 225 | status++; |
soulx | 12:2564eac22e0a | 226 | } |
soulx | 12:2564eac22e0a | 227 | } |
soulx | 12:2564eac22e0a | 228 | |
soulx | 12:2564eac22e0a | 229 | if(status == 0) { |
soulx | 12:2564eac22e0a | 230 | state =0; |
soulx | 12:2564eac22e0a | 231 | // sleep |
soulx | 12:2564eac22e0a | 232 | state += leg_left_upper.position_control(0); |
soulx | 12:2564eac22e0a | 233 | state += leg_right_upper.position_control(0); |
soulx | 12:2564eac22e0a | 234 | state += leg_left_lower.position_control(64); |
soulx | 12:2564eac22e0a | 235 | state += leg_right_lower.position_control(64); |
soulx | 12:2564eac22e0a | 236 | if(state == 8) { |
soulx | 12:2564eac22e0a | 237 | myled=1; |
soulx | 12:2564eac22e0a | 238 | } else { |
soulx | 12:2564eac22e0a | 239 | myled=0; |
soulx | 12:2564eac22e0a | 240 | } |
soulx | 12:2564eac22e0a | 241 | } else if(status == 1 || status ==3) { |
soulx | 12:2564eac22e0a | 242 | state =0; |
soulx | 12:2564eac22e0a | 243 | // sit |
soulx | 12:2564eac22e0a | 244 | state += leg_left_upper.position_control(64); |
soulx | 12:2564eac22e0a | 245 | state += leg_right_upper.position_control(64); |
soulx | 12:2564eac22e0a | 246 | state += leg_left_lower.position_control(64); |
soulx | 12:2564eac22e0a | 247 | state += leg_right_lower.position_control(64); |
soulx | 12:2564eac22e0a | 248 | if(state == 8) { |
soulx | 12:2564eac22e0a | 249 | myled=1; |
soulx | 12:2564eac22e0a | 250 | } else { |
soulx | 12:2564eac22e0a | 251 | myled=0; |
soulx | 12:2564eac22e0a | 252 | } |
soulx | 12:2564eac22e0a | 253 | } else if(status == 2) { |
soulx | 12:2564eac22e0a | 254 | state =0; |
soulx | 12:2564eac22e0a | 255 | // stand |
soulx | 16:ec0cba3631bc | 256 | state += leg_left_upper.position_control(63); |
soulx | 16:ec0cba3631bc | 257 | state += leg_right_upper.position_control(56); |
soulx | 16:ec0cba3631bc | 258 | state += leg_left_lower.position_control(7); |
soulx | 16:ec0cba3631bc | 259 | state += leg_right_lower.position_control(10); |
soulx | 12:2564eac22e0a | 260 | if(state == 8) { |
soulx | 12:2564eac22e0a | 261 | myled=1; |
soulx | 12:2564eac22e0a | 262 | } else { |
soulx | 12:2564eac22e0a | 263 | myled=0; |
soulx | 12:2564eac22e0a | 264 | } |
soulx | 12:2564eac22e0a | 265 | } |
soulx | 12:2564eac22e0a | 266 | } |
soulx | 12:2564eac22e0a | 267 | //t.stop(); |
soulx | 12:2564eac22e0a | 268 | } |
soulx | 12:2564eac22e0a | 269 | |
soulx | 12:2564eac22e0a | 270 | void management(ANDANTE_PROTOCOL_PACKET *packet) |
soulx | 12:2564eac22e0a | 271 | { |
soulx | 12:2564eac22e0a | 272 | switch(packet->instructionErrorId) { |
soulx | 12:2564eac22e0a | 273 | case 0x01: |
soulx | 16:ec0cba3631bc | 274 | buff1.left_up = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 275 | break; |
soulx | 12:2564eac22e0a | 276 | case 0x02: |
soulx | 16:ec0cba3631bc | 277 | buff1.left_down = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 278 | break; |
soulx | 12:2564eac22e0a | 279 | case 0x03: |
soulx | 16:ec0cba3631bc | 280 | buff1.right_up = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 281 | break; |
soulx | 12:2564eac22e0a | 282 | case 0x04: |
soulx | 16:ec0cba3631bc | 283 | buff1.right_down = Utilities::ConvertUInt8ArrayToInt16(packet->parameter); |
soulx | 12:2564eac22e0a | 284 | break; |
soulx | 12:2564eac22e0a | 285 | } |
soulx | 12:2564eac22e0a | 286 | } |
soulx | 12:2564eac22e0a | 287 | |
soulx | 12:2564eac22e0a | 288 | void routine() |
soulx | 12:2564eac22e0a | 289 | { |
soulx | 12:2564eac22e0a | 290 | uint8_t state=0; |
soulx | 12:2564eac22e0a | 291 | // PARAM_WRITE pos = buff; |
soulx | 12:2564eac22e0a | 292 | while(1) { |
soulx | 12:2564eac22e0a | 293 | state =0; |
soulx | 12:2564eac22e0a | 294 | // sit |
soulx | 16:ec0cba3631bc | 295 | state += leg_left_upper.position_control(buff1.left_up); |
soulx | 16:ec0cba3631bc | 296 | state += leg_right_upper.position_control(buff1.right_up); |
soulx | 16:ec0cba3631bc | 297 | state += leg_left_lower.position_control(buff1.left_down); |
soulx | 16:ec0cba3631bc | 298 | state += leg_right_lower.position_control(buff1.right_down); |
soulx | 12:2564eac22e0a | 299 | if(state == 8) { |
soulx | 12:2564eac22e0a | 300 | myled=1; |
soulx | 12:2564eac22e0a | 301 | } else { |
soulx | 12:2564eac22e0a | 302 | myled=0; |
soulx | 12:2564eac22e0a | 303 | } |
soulx | 12:2564eac22e0a | 304 | } |
soulx | 12:2564eac22e0a | 305 | } |
soulx | 12:2564eac22e0a | 306 | |
soulx | 12:2564eac22e0a | 307 | void test_limit() |
soulx | 12:2564eac22e0a | 308 | { |
soulx | 12:2564eac22e0a | 309 | pc.printf("TEST LIMIT ALL\n"); |
soulx | 16:ec0cba3631bc | 310 | t.start(); |
soulx | 16:ec0cba3631bc | 311 | while(1) { |
soulx | 13:218c22a620cc | 312 | if(t.read() > 1.0f) { |
soulx | 13:218c22a620cc | 313 | t.reset(); |
soulx | 13:218c22a620cc | 314 | pc.printf("leftUP_limit_up = "); |
soulx | 13:218c22a620cc | 315 | if(leg_left_upper.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 316 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 317 | else |
soulx | 13:218c22a620cc | 318 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 319 | |
soulx | 13:218c22a620cc | 320 | pc.printf("leftUP_limit_down = "); |
soulx | 13:218c22a620cc | 321 | if(leg_left_upper.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 322 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 323 | else |
soulx | 13:218c22a620cc | 324 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 325 | |
soulx | 13:218c22a620cc | 326 | pc.printf("leftLOW_limit_up = "); |
soulx | 13:218c22a620cc | 327 | if(leg_left_lower.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 328 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 329 | else |
soulx | 13:218c22a620cc | 330 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 331 | |
soulx | 13:218c22a620cc | 332 | pc.printf("leftLow_limit_down = "); |
soulx | 13:218c22a620cc | 333 | if(leg_left_lower.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 334 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 335 | else |
soulx | 13:218c22a620cc | 336 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 337 | |
soulx | 12:2564eac22e0a | 338 | /////////////////////////////////////////////////////////////// |
soulx | 13:218c22a620cc | 339 | pc.printf("rightUP_limit_up = "); |
soulx | 13:218c22a620cc | 340 | if(leg_right_upper.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 341 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 342 | else |
soulx | 13:218c22a620cc | 343 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 344 | |
soulx | 13:218c22a620cc | 345 | pc.printf("rightUP_limit_down = "); |
soulx | 13:218c22a620cc | 346 | if(leg_right_upper.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 347 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 348 | else |
soulx | 13:218c22a620cc | 349 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 350 | |
soulx | 13:218c22a620cc | 351 | pc.printf("rightLOW_limit_up = "); |
soulx | 13:218c22a620cc | 352 | if(leg_right_lower.GetLimitUp() == 1) |
soulx | 13:218c22a620cc | 353 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 354 | else |
soulx | 13:218c22a620cc | 355 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 356 | |
soulx | 13:218c22a620cc | 357 | pc.printf("rightLow_limit_down = "); |
soulx | 13:218c22a620cc | 358 | if(leg_right_lower.GetLimitDown() == 1) |
soulx | 13:218c22a620cc | 359 | pc.printf("shot\n"); |
soulx | 13:218c22a620cc | 360 | else |
soulx | 13:218c22a620cc | 361 | pc.printf("open\n"); |
soulx | 12:2564eac22e0a | 362 | |
soulx | 13:218c22a620cc | 363 | pc.printf("\n\n"); |
soulx | 13:218c22a620cc | 364 | } |
soulx | 16:ec0cba3631bc | 365 | } |
soulx | 16:ec0cba3631bc | 366 | //t.stop(); |
soulx | 12:2564eac22e0a | 367 | } |
soulx | 12:2564eac22e0a | 368 | |
soulx | 12:2564eac22e0a | 369 | void test_motor() |
soulx | 12:2564eac22e0a | 370 | { |
soulx | 12:2564eac22e0a | 371 | uint8_t state=0; |
soulx | 12:2564eac22e0a | 372 | |
soulx | 12:2564eac22e0a | 373 | pc.printf("TEST MOTOR DELAY\n"); |
soulx | 12:2564eac22e0a | 374 | t.start(); |
soulx | 12:2564eac22e0a | 375 | while(1) { |
soulx | 12:2564eac22e0a | 376 | if(t.read() > 1.5f) { |
soulx | 12:2564eac22e0a | 377 | t.reset(); |
soulx | 12:2564eac22e0a | 378 | if(state >1) { |
soulx | 12:2564eac22e0a | 379 | state =0; |
soulx | 12:2564eac22e0a | 380 | } else { |
soulx | 12:2564eac22e0a | 381 | state++; |
soulx | 12:2564eac22e0a | 382 | } |
soulx | 12:2564eac22e0a | 383 | } |
soulx | 12:2564eac22e0a | 384 | |
soulx | 12:2564eac22e0a | 385 | if(state ==0) { |
soulx | 12:2564eac22e0a | 386 | leg_left_upper.limit_motor(1); |
soulx | 12:2564eac22e0a | 387 | leg_right_upper.limit_motor(1); |
soulx | 12:2564eac22e0a | 388 | leg_left_lower.limit_motor(1); |
soulx | 12:2564eac22e0a | 389 | leg_right_lower.limit_motor(1); |
soulx | 12:2564eac22e0a | 390 | } else { |
soulx | 12:2564eac22e0a | 391 | { |
soulx | 12:2564eac22e0a | 392 | leg_left_upper.limit_motor(2); |
soulx | 12:2564eac22e0a | 393 | leg_right_upper.limit_motor(2); |
soulx | 12:2564eac22e0a | 394 | leg_left_lower.limit_motor(2); |
soulx | 12:2564eac22e0a | 395 | leg_right_lower.limit_motor(2); |
soulx | 12:2564eac22e0a | 396 | } |
soulx | 12:2564eac22e0a | 397 | } |
soulx | 12:2564eac22e0a | 398 | } |
soulx | 13:218c22a620cc | 399 | } |
soulx | 13:218c22a620cc | 400 | |
soulx | 13:218c22a620cc | 401 | void serial_control() |
soulx | 13:218c22a620cc | 402 | { |
soulx | 13:218c22a620cc | 403 | |
soulx | 14:7fe99764b2d0 | 404 | uint16_t left_up=63; |
soulx | 13:218c22a620cc | 405 | uint16_t left_down=0; |
soulx | 14:7fe99764b2d0 | 406 | uint16_t right_up=63; |
soulx | 13:218c22a620cc | 407 | uint16_t right_down=0; |
soulx | 13:218c22a620cc | 408 | |
soulx | 14:7fe99764b2d0 | 409 | uint16_t offset_ll=11400; |
soulx | 14:7fe99764b2d0 | 410 | uint16_t offset_rl=17800; |
soulx | 13:218c22a620cc | 411 | |
soulx | 13:218c22a620cc | 412 | uint8_t state=0; |
soulx | 13:218c22a620cc | 413 | |
soulx | 13:218c22a620cc | 414 | t.start(); |
soulx | 13:218c22a620cc | 415 | |
soulx | 13:218c22a620cc | 416 | while(1) { |
soulx | 13:218c22a620cc | 417 | if(pc.readable() == 1) { |
soulx | 13:218c22a620cc | 418 | serial_data = pc.getc(); |
soulx | 13:218c22a620cc | 419 | } |
soulx | 13:218c22a620cc | 420 | |
soulx | 13:218c22a620cc | 421 | switch(serial_data) { |
soulx | 13:218c22a620cc | 422 | case 'q': |
soulx | 14:7fe99764b2d0 | 423 | if(left_up >=63) { |
soulx | 13:218c22a620cc | 424 | left_up= 63; |
soulx | 13:218c22a620cc | 425 | } else { |
soulx | 13:218c22a620cc | 426 | left_up++; |
soulx | 13:218c22a620cc | 427 | } |
soulx | 14:7fe99764b2d0 | 428 | serial_data=0; |
soulx | 13:218c22a620cc | 429 | break; |
soulx | 13:218c22a620cc | 430 | |
soulx | 13:218c22a620cc | 431 | case 'a': |
soulx | 16:ec0cba3631bc | 432 | if(left_up ==0) { |
soulx | 13:218c22a620cc | 433 | left_up= 0; |
soulx | 13:218c22a620cc | 434 | } else { |
soulx | 13:218c22a620cc | 435 | left_up--; |
soulx | 13:218c22a620cc | 436 | } |
soulx | 14:7fe99764b2d0 | 437 | serial_data=0; |
soulx | 13:218c22a620cc | 438 | break; |
soulx | 13:218c22a620cc | 439 | |
soulx | 13:218c22a620cc | 440 | case 'z': |
soulx | 14:7fe99764b2d0 | 441 | if(left_up >=53) { |
soulx | 13:218c22a620cc | 442 | left_up= 63; |
soulx | 13:218c22a620cc | 443 | } else { |
soulx | 13:218c22a620cc | 444 | left_up+=10; |
soulx | 13:218c22a620cc | 445 | } |
soulx | 14:7fe99764b2d0 | 446 | serial_data=0; |
soulx | 13:218c22a620cc | 447 | break; |
soulx | 13:218c22a620cc | 448 | |
soulx | 13:218c22a620cc | 449 | case 'Z': |
soulx | 16:ec0cba3631bc | 450 | if(left_up <=10) { |
soulx | 13:218c22a620cc | 451 | left_up= 0; |
soulx | 13:218c22a620cc | 452 | } else { |
soulx | 13:218c22a620cc | 453 | left_up-=10; |
soulx | 13:218c22a620cc | 454 | } |
soulx | 14:7fe99764b2d0 | 455 | serial_data=0; |
soulx | 13:218c22a620cc | 456 | break; |
soulx | 13:218c22a620cc | 457 | |
soulx | 13:218c22a620cc | 458 | case 'w': |
soulx | 14:7fe99764b2d0 | 459 | if(left_down >=63) { |
soulx | 13:218c22a620cc | 460 | left_down= 63; |
soulx | 13:218c22a620cc | 461 | } else { |
soulx | 13:218c22a620cc | 462 | left_down++; |
soulx | 13:218c22a620cc | 463 | } |
soulx | 14:7fe99764b2d0 | 464 | serial_data=0; |
soulx | 13:218c22a620cc | 465 | break; |
soulx | 13:218c22a620cc | 466 | |
soulx | 13:218c22a620cc | 467 | case 's': |
soulx | 16:ec0cba3631bc | 468 | if(left_down ==0) { |
soulx | 13:218c22a620cc | 469 | left_down= 0; |
soulx | 13:218c22a620cc | 470 | } else { |
soulx | 13:218c22a620cc | 471 | left_down--; |
soulx | 13:218c22a620cc | 472 | } |
soulx | 14:7fe99764b2d0 | 473 | serial_data=0; |
soulx | 13:218c22a620cc | 474 | break; |
soulx | 13:218c22a620cc | 475 | |
soulx | 13:218c22a620cc | 476 | case 'x': |
soulx | 14:7fe99764b2d0 | 477 | if(left_down >=53) { |
soulx | 13:218c22a620cc | 478 | left_down= 63; |
soulx | 13:218c22a620cc | 479 | } else { |
soulx | 13:218c22a620cc | 480 | left_down+=10; |
soulx | 13:218c22a620cc | 481 | } |
soulx | 14:7fe99764b2d0 | 482 | serial_data=0; |
soulx | 13:218c22a620cc | 483 | break; |
soulx | 13:218c22a620cc | 484 | |
soulx | 13:218c22a620cc | 485 | case 'X': |
soulx | 16:ec0cba3631bc | 486 | if(left_down <=10) { |
soulx | 13:218c22a620cc | 487 | left_down= 0; |
soulx | 13:218c22a620cc | 488 | } else { |
soulx | 13:218c22a620cc | 489 | left_down-=10; |
soulx | 13:218c22a620cc | 490 | } |
soulx | 14:7fe99764b2d0 | 491 | serial_data=0; |
soulx | 13:218c22a620cc | 492 | break; |
soulx | 13:218c22a620cc | 493 | |
soulx | 13:218c22a620cc | 494 | |
soulx | 13:218c22a620cc | 495 | case 'e': |
soulx | 14:7fe99764b2d0 | 496 | if(right_up >=63) { |
soulx | 13:218c22a620cc | 497 | right_up= 63; |
soulx | 13:218c22a620cc | 498 | } else { |
soulx | 13:218c22a620cc | 499 | right_up++; |
soulx | 13:218c22a620cc | 500 | } |
soulx | 14:7fe99764b2d0 | 501 | serial_data=0; |
soulx | 13:218c22a620cc | 502 | break; |
soulx | 13:218c22a620cc | 503 | |
soulx | 13:218c22a620cc | 504 | case 'd': |
soulx | 16:ec0cba3631bc | 505 | if(right_up ==0) { |
soulx | 13:218c22a620cc | 506 | right_up= 0; |
soulx | 13:218c22a620cc | 507 | } else { |
soulx | 13:218c22a620cc | 508 | right_up--; |
soulx | 13:218c22a620cc | 509 | } |
soulx | 14:7fe99764b2d0 | 510 | serial_data=0; |
soulx | 13:218c22a620cc | 511 | break; |
soulx | 13:218c22a620cc | 512 | |
soulx | 13:218c22a620cc | 513 | case 'c': |
soulx | 14:7fe99764b2d0 | 514 | if(right_up >=53) { |
soulx | 13:218c22a620cc | 515 | right_up= 63; |
soulx | 13:218c22a620cc | 516 | } else { |
soulx | 13:218c22a620cc | 517 | right_up+=10; |
soulx | 13:218c22a620cc | 518 | } |
soulx | 14:7fe99764b2d0 | 519 | serial_data=0; |
soulx | 13:218c22a620cc | 520 | break; |
soulx | 13:218c22a620cc | 521 | |
soulx | 13:218c22a620cc | 522 | case 'C': |
soulx | 16:ec0cba3631bc | 523 | if(right_up <=10) { |
soulx | 13:218c22a620cc | 524 | right_up= 0; |
soulx | 13:218c22a620cc | 525 | } else { |
soulx | 13:218c22a620cc | 526 | right_up-=10; |
soulx | 13:218c22a620cc | 527 | } |
soulx | 14:7fe99764b2d0 | 528 | serial_data=0; |
soulx | 13:218c22a620cc | 529 | break; |
soulx | 13:218c22a620cc | 530 | |
soulx | 13:218c22a620cc | 531 | |
soulx | 13:218c22a620cc | 532 | |
soulx | 13:218c22a620cc | 533 | |
soulx | 13:218c22a620cc | 534 | case 'r': |
soulx | 14:7fe99764b2d0 | 535 | if(right_down >=63) { |
soulx | 13:218c22a620cc | 536 | right_down= 63; |
soulx | 13:218c22a620cc | 537 | } else { |
soulx | 13:218c22a620cc | 538 | right_down++; |
soulx | 13:218c22a620cc | 539 | } |
soulx | 14:7fe99764b2d0 | 540 | serial_data=0; |
soulx | 13:218c22a620cc | 541 | break; |
soulx | 13:218c22a620cc | 542 | |
soulx | 13:218c22a620cc | 543 | case 'f': |
soulx | 16:ec0cba3631bc | 544 | if(right_down <=0) { |
soulx | 13:218c22a620cc | 545 | right_down= 0; |
soulx | 13:218c22a620cc | 546 | } else { |
soulx | 13:218c22a620cc | 547 | right_down--; |
soulx | 13:218c22a620cc | 548 | } |
soulx | 14:7fe99764b2d0 | 549 | serial_data=0; |
soulx | 14:7fe99764b2d0 | 550 | |
soulx | 13:218c22a620cc | 551 | break; |
soulx | 13:218c22a620cc | 552 | |
soulx | 13:218c22a620cc | 553 | case 'v': |
soulx | 14:7fe99764b2d0 | 554 | if(right_down >=53) { |
soulx | 13:218c22a620cc | 555 | right_down= 63; |
soulx | 13:218c22a620cc | 556 | } else { |
soulx | 13:218c22a620cc | 557 | right_down+=10; |
soulx | 13:218c22a620cc | 558 | } |
soulx | 14:7fe99764b2d0 | 559 | serial_data=0; |
soulx | 14:7fe99764b2d0 | 560 | |
soulx | 13:218c22a620cc | 561 | break; |
soulx | 13:218c22a620cc | 562 | |
soulx | 13:218c22a620cc | 563 | case 'V': |
soulx | 16:ec0cba3631bc | 564 | if(right_down <=10) { |
soulx | 13:218c22a620cc | 565 | right_down= 0; |
soulx | 13:218c22a620cc | 566 | } else { |
soulx | 13:218c22a620cc | 567 | right_down-=10; |
soulx | 13:218c22a620cc | 568 | } |
soulx | 14:7fe99764b2d0 | 569 | serial_data=0; |
soulx | 13:218c22a620cc | 570 | break; |
soulx | 13:218c22a620cc | 571 | |
soulx | 13:218c22a620cc | 572 | case 'p': |
soulx | 13:218c22a620cc | 573 | test_status(); |
soulx | 13:218c22a620cc | 574 | break; |
soulx | 13:218c22a620cc | 575 | |
soulx | 14:7fe99764b2d0 | 576 | case '7': |
soulx | 14:7fe99764b2d0 | 577 | test_sleep(); |
soulx | 14:7fe99764b2d0 | 578 | break; |
soulx | 14:7fe99764b2d0 | 579 | |
soulx | 14:7fe99764b2d0 | 580 | case '8': |
soulx | 14:7fe99764b2d0 | 581 | test_sit(); |
soulx | 14:7fe99764b2d0 | 582 | break; |
soulx | 14:7fe99764b2d0 | 583 | |
soulx | 14:7fe99764b2d0 | 584 | case '9': |
soulx | 16:ec0cba3631bc | 585 | test_stand(buff1); |
soulx | 14:7fe99764b2d0 | 586 | break; |
soulx | 14:7fe99764b2d0 | 587 | |
soulx | 13:218c22a620cc | 588 | case 'y': |
soulx | 13:218c22a620cc | 589 | if(offset_ll > 30000) { |
soulx | 13:218c22a620cc | 590 | offset_ll =30000; |
soulx | 13:218c22a620cc | 591 | } else { |
soulx | 13:218c22a620cc | 592 | |
soulx | 13:218c22a620cc | 593 | offset_ll+=100; |
soulx | 13:218c22a620cc | 594 | } |
soulx | 13:218c22a620cc | 595 | leg_left_lower.SetOffset(offset_ll); |
soulx | 14:7fe99764b2d0 | 596 | serial_data=0; |
soulx | 13:218c22a620cc | 597 | break; |
soulx | 13:218c22a620cc | 598 | |
soulx | 13:218c22a620cc | 599 | case 'h': |
soulx | 13:218c22a620cc | 600 | if(offset_ll <= 100) { |
soulx | 13:218c22a620cc | 601 | offset_ll =0; |
soulx | 13:218c22a620cc | 602 | } else { |
soulx | 13:218c22a620cc | 603 | |
soulx | 13:218c22a620cc | 604 | offset_ll-=100; |
soulx | 13:218c22a620cc | 605 | } |
soulx | 13:218c22a620cc | 606 | leg_left_lower.SetOffset(offset_ll); |
soulx | 14:7fe99764b2d0 | 607 | serial_data=0; |
soulx | 13:218c22a620cc | 608 | break; |
soulx | 13:218c22a620cc | 609 | |
soulx | 13:218c22a620cc | 610 | case 'u': |
soulx | 13:218c22a620cc | 611 | if(offset_rl > 30000) { |
soulx | 13:218c22a620cc | 612 | offset_rl =30000; |
soulx | 13:218c22a620cc | 613 | } else { |
soulx | 13:218c22a620cc | 614 | |
soulx | 13:218c22a620cc | 615 | offset_rl+=100; |
soulx | 13:218c22a620cc | 616 | } |
soulx | 13:218c22a620cc | 617 | leg_right_lower.SetOffset(offset_rl); |
soulx | 14:7fe99764b2d0 | 618 | serial_data=0; |
soulx | 13:218c22a620cc | 619 | break; |
soulx | 13:218c22a620cc | 620 | |
soulx | 13:218c22a620cc | 621 | case 'j': |
soulx | 13:218c22a620cc | 622 | if(offset_rl <= 100) { |
soulx | 13:218c22a620cc | 623 | offset_rl =0; |
soulx | 13:218c22a620cc | 624 | } else { |
soulx | 13:218c22a620cc | 625 | |
soulx | 13:218c22a620cc | 626 | offset_rl-=100; |
soulx | 13:218c22a620cc | 627 | } |
soulx | 13:218c22a620cc | 628 | leg_right_lower.SetOffset(offset_rl); |
soulx | 14:7fe99764b2d0 | 629 | serial_data=0; |
soulx | 13:218c22a620cc | 630 | break; |
soulx | 13:218c22a620cc | 631 | |
soulx | 14:7fe99764b2d0 | 632 | case '0': |
soulx | 13:218c22a620cc | 633 | leg_left_lower.SetMode(0); |
soulx | 13:218c22a620cc | 634 | leg_right_lower.SetMode(0); |
soulx | 13:218c22a620cc | 635 | pc.printf("MODE 0:ON\n"); |
soulx | 14:7fe99764b2d0 | 636 | serial_data=0; |
soulx | 13:218c22a620cc | 637 | break; |
soulx | 13:218c22a620cc | 638 | case '1': |
soulx | 13:218c22a620cc | 639 | leg_left_lower.SetMode(1); |
soulx | 13:218c22a620cc | 640 | leg_right_lower.SetMode(1); |
soulx | 13:218c22a620cc | 641 | pc.printf("MODE 1:ON\n"); |
soulx | 14:7fe99764b2d0 | 642 | serial_data=0; |
soulx | 13:218c22a620cc | 643 | break; |
soulx | 13:218c22a620cc | 644 | case '2': |
soulx | 13:218c22a620cc | 645 | leg_left_lower.SetMode(2); |
soulx | 13:218c22a620cc | 646 | leg_right_lower.SetMode(2); |
soulx | 13:218c22a620cc | 647 | pc.printf("MODE 2:ON\n"); |
soulx | 14:7fe99764b2d0 | 648 | serial_data=0; |
soulx | 14:7fe99764b2d0 | 649 | break; |
soulx | 14:7fe99764b2d0 | 650 | case '5': |
soulx | 14:7fe99764b2d0 | 651 | wheel.reset(); |
soulx | 14:7fe99764b2d0 | 652 | serial_data=0; |
soulx | 14:7fe99764b2d0 | 653 | break; |
soulx | 14:7fe99764b2d0 | 654 | |
soulx | 14:7fe99764b2d0 | 655 | case '[': |
soulx | 14:7fe99764b2d0 | 656 | test_limit(); |
soulx | 13:218c22a620cc | 657 | break; |
soulx | 16:ec0cba3631bc | 658 | |
soulx | 16:ec0cba3631bc | 659 | case 'n': |
soulx | 16:ec0cba3631bc | 660 | buff1.left_up = left_up; |
soulx | 16:ec0cba3631bc | 661 | buff1.left_down = left_down; |
soulx | 16:ec0cba3631bc | 662 | buff1.right_up = right_up; |
soulx | 16:ec0cba3631bc | 663 | buff1.right_down =right_down; |
soulx | 16:ec0cba3631bc | 664 | break; |
soulx | 16:ec0cba3631bc | 665 | |
soulx | 16:ec0cba3631bc | 666 | case 'm': |
soulx | 16:ec0cba3631bc | 667 | buff2.left_up = left_up; |
soulx | 16:ec0cba3631bc | 668 | buff2.left_down = left_down; |
soulx | 16:ec0cba3631bc | 669 | buff2.right_up = right_up; |
soulx | 16:ec0cba3631bc | 670 | buff2.right_down =right_down; |
soulx | 16:ec0cba3631bc | 671 | break; |
soulx | 16:ec0cba3631bc | 672 | |
soulx | 16:ec0cba3631bc | 673 | case 'b': |
soulx | 16:ec0cba3631bc | 674 | test_status2(buff1,buff2); |
soulx | 16:ec0cba3631bc | 675 | break; |
soulx | 16:ec0cba3631bc | 676 | |
soulx | 13:218c22a620cc | 677 | } |
soulx | 13:218c22a620cc | 678 | |
soulx | 14:7fe99764b2d0 | 679 | if(t.read() > 0.7f) { |
soulx | 13:218c22a620cc | 680 | t.reset(); |
soulx | 13:218c22a620cc | 681 | pc.printf("left_up %d\n",left_up); |
soulx | 13:218c22a620cc | 682 | pc.printf("left_down %d\n",left_down); |
soulx | 13:218c22a620cc | 683 | pc.printf("right_up %d\n",right_up); |
soulx | 13:218c22a620cc | 684 | pc.printf("right_down %d\n",right_down); |
soulx | 13:218c22a620cc | 685 | pc.printf("offset_ll %d\n",offset_ll); |
soulx | 13:218c22a620cc | 686 | pc.printf("offset_rl %d\n",offset_rl); |
soulx | 14:7fe99764b2d0 | 687 | pc.printf("Pulses is: %i\n", wheel.getPulses()); |
soulx | 13:218c22a620cc | 688 | pc.printf("\n"); |
soulx | 13:218c22a620cc | 689 | |
soulx | 13:218c22a620cc | 690 | } |
soulx | 14:7fe99764b2d0 | 691 | //serial_data=0; |
soulx | 13:218c22a620cc | 692 | state =0; |
soulx | 13:218c22a620cc | 693 | |
soulx | 14:7fe99764b2d0 | 694 | if(serial_data ==0) { |
soulx | 14:7fe99764b2d0 | 695 | state += leg_left_upper.position_control(left_up); |
soulx | 14:7fe99764b2d0 | 696 | state += leg_right_upper.position_control(right_up); |
soulx | 14:7fe99764b2d0 | 697 | state += leg_left_lower.position_control(left_down); |
soulx | 14:7fe99764b2d0 | 698 | state += leg_right_lower.position_control(right_down); |
soulx | 14:7fe99764b2d0 | 699 | if(state == 8) { |
soulx | 14:7fe99764b2d0 | 700 | myled=1; |
soulx | 14:7fe99764b2d0 | 701 | } else { |
soulx | 14:7fe99764b2d0 | 702 | myled=0; |
soulx | 14:7fe99764b2d0 | 703 | } |
soulx | 13:218c22a620cc | 704 | } |
soulx | 13:218c22a620cc | 705 | } |
soulx | 14:7fe99764b2d0 | 706 | } |
soulx | 14:7fe99764b2d0 | 707 | |
soulx | 14:7fe99764b2d0 | 708 | void test_limit_motor(uint8_t dirction) |
soulx | 14:7fe99764b2d0 | 709 | { |
soulx | 14:7fe99764b2d0 | 710 | int state; |
soulx | 14:7fe99764b2d0 | 711 | while(1) { |
soulx | 14:7fe99764b2d0 | 712 | state = leg_left_upper.limit_motor(dirction); |
soulx | 14:7fe99764b2d0 | 713 | pc.printf("state_lu %d\n",state); |
soulx | 14:7fe99764b2d0 | 714 | state = leg_left_lower.limit_motor(dirction); |
soulx | 14:7fe99764b2d0 | 715 | pc.printf("state_ll %d\n",state); |
soulx | 14:7fe99764b2d0 | 716 | state = leg_right_upper.limit_motor(dirction); |
soulx | 14:7fe99764b2d0 | 717 | pc.printf("state_ru %d\n",state); |
soulx | 14:7fe99764b2d0 | 718 | state = leg_right_lower.limit_motor(dirction); |
soulx | 14:7fe99764b2d0 | 719 | pc.printf("state_rl %d\n",state); |
soulx | 14:7fe99764b2d0 | 720 | } |
soulx | 14:7fe99764b2d0 | 721 | } |
soulx | 14:7fe99764b2d0 | 722 | |
soulx | 14:7fe99764b2d0 | 723 | void test_sit() |
soulx | 14:7fe99764b2d0 | 724 | { |
soulx | 14:7fe99764b2d0 | 725 | uint16_t state=0; |
soulx | 14:7fe99764b2d0 | 726 | // pc.printf("Test_sit\n"); |
soulx | 14:7fe99764b2d0 | 727 | //t.start(); |
soulx | 14:7fe99764b2d0 | 728 | // while(1) { |
soulx | 14:7fe99764b2d0 | 729 | // sit |
soulx | 14:7fe99764b2d0 | 730 | state += leg_left_upper.position_control(64); |
soulx | 14:7fe99764b2d0 | 731 | state += leg_right_upper.position_control(64); |
soulx | 14:7fe99764b2d0 | 732 | state += leg_left_lower.position_control(64); |
soulx | 14:7fe99764b2d0 | 733 | state += leg_right_lower.position_control(64); |
soulx | 14:7fe99764b2d0 | 734 | if(state == 8) { |
soulx | 14:7fe99764b2d0 | 735 | myled=1; |
soulx | 14:7fe99764b2d0 | 736 | } else { |
soulx | 14:7fe99764b2d0 | 737 | myled=0; |
soulx | 14:7fe99764b2d0 | 738 | } |
soulx | 14:7fe99764b2d0 | 739 | |
soulx | 14:7fe99764b2d0 | 740 | // } |
soulx | 14:7fe99764b2d0 | 741 | } |
soulx | 14:7fe99764b2d0 | 742 | |
soulx | 16:ec0cba3631bc | 743 | void test_stand(PARAM_WRITE d1) |
soulx | 14:7fe99764b2d0 | 744 | { |
soulx | 14:7fe99764b2d0 | 745 | uint16_t state=0; |
soulx | 14:7fe99764b2d0 | 746 | // pc.printf("Test_stand\n"); |
soulx | 14:7fe99764b2d0 | 747 | // t.start(); |
soulx | 16:ec0cba3631bc | 748 | while(1) { |
soulx | 14:7fe99764b2d0 | 749 | |
soulx | 14:7fe99764b2d0 | 750 | // stand |
soulx | 16:ec0cba3631bc | 751 | state += leg_left_upper.position_control(d1.left_up); |
soulx | 16:ec0cba3631bc | 752 | state += leg_right_upper.position_control(d1.right_up); |
soulx | 16:ec0cba3631bc | 753 | state += leg_left_lower.position_control(d1.left_down); |
soulx | 16:ec0cba3631bc | 754 | state += leg_right_lower.position_control(d1.right_down); |
soulx | 14:7fe99764b2d0 | 755 | if(state == 8) { |
soulx | 14:7fe99764b2d0 | 756 | myled=1; |
soulx | 14:7fe99764b2d0 | 757 | } else { |
soulx | 14:7fe99764b2d0 | 758 | myled=0; |
soulx | 14:7fe99764b2d0 | 759 | } |
soulx | 16:ec0cba3631bc | 760 | } |
soulx | 14:7fe99764b2d0 | 761 | } |
soulx | 14:7fe99764b2d0 | 762 | |
soulx | 14:7fe99764b2d0 | 763 | void test_sleep() |
soulx | 14:7fe99764b2d0 | 764 | { |
soulx | 14:7fe99764b2d0 | 765 | uint16_t state=0; |
soulx | 14:7fe99764b2d0 | 766 | // pc.printf("Test_sleep\n"); |
soulx | 14:7fe99764b2d0 | 767 | // t.start(); |
soulx | 14:7fe99764b2d0 | 768 | // while(1) { |
soulx | 14:7fe99764b2d0 | 769 | |
soulx | 14:7fe99764b2d0 | 770 | // sleep |
soulx | 14:7fe99764b2d0 | 771 | state += leg_left_upper.position_control(0); |
soulx | 14:7fe99764b2d0 | 772 | state += leg_right_upper.position_control(0); |
soulx | 14:7fe99764b2d0 | 773 | state += leg_left_lower.position_control(64); |
soulx | 14:7fe99764b2d0 | 774 | state += leg_right_lower.position_control(64); |
soulx | 14:7fe99764b2d0 | 775 | if(state == 8) { |
soulx | 14:7fe99764b2d0 | 776 | myled=1; |
soulx | 14:7fe99764b2d0 | 777 | } else { |
soulx | 14:7fe99764b2d0 | 778 | myled=0; |
soulx | 14:7fe99764b2d0 | 779 | } |
soulx | 14:7fe99764b2d0 | 780 | // } |
soulx | 16:ec0cba3631bc | 781 | } |
soulx | 16:ec0cba3631bc | 782 | |
soulx | 16:ec0cba3631bc | 783 | void test_status2(PARAM_WRITE d1, PARAM_WRITE d2) |
soulx | 16:ec0cba3631bc | 784 | { |
soulx | 16:ec0cba3631bc | 785 | uint16_t state=0; |
soulx | 16:ec0cba3631bc | 786 | pc.printf("Test_status\n"); |
soulx | 16:ec0cba3631bc | 787 | t.start(); |
soulx | 16:ec0cba3631bc | 788 | while(1) { |
soulx | 16:ec0cba3631bc | 789 | |
soulx | 16:ec0cba3631bc | 790 | if(pc.readable() == 1) { |
soulx | 16:ec0cba3631bc | 791 | serial_data = pc.getc(); |
soulx | 16:ec0cba3631bc | 792 | } |
soulx | 16:ec0cba3631bc | 793 | |
soulx | 16:ec0cba3631bc | 794 | if(t.read() > 30.0f) { |
soulx | 16:ec0cba3631bc | 795 | t.reset(); |
soulx | 16:ec0cba3631bc | 796 | if(status >=1) { |
soulx | 16:ec0cba3631bc | 797 | status =0; |
soulx | 16:ec0cba3631bc | 798 | } else { |
soulx | 16:ec0cba3631bc | 799 | status++; |
soulx | 16:ec0cba3631bc | 800 | } |
soulx | 16:ec0cba3631bc | 801 | } |
soulx | 16:ec0cba3631bc | 802 | |
soulx | 16:ec0cba3631bc | 803 | if(status == 0) { |
soulx | 16:ec0cba3631bc | 804 | state =0; |
soulx | 16:ec0cba3631bc | 805 | // sleep |
soulx | 16:ec0cba3631bc | 806 | state += leg_left_upper.position_control(d1.left_up); |
soulx | 16:ec0cba3631bc | 807 | state += leg_right_upper.position_control(d1.right_up); |
soulx | 16:ec0cba3631bc | 808 | state += leg_left_lower.position_control(d1.left_down); |
soulx | 16:ec0cba3631bc | 809 | state += leg_right_lower.position_control(d1.right_down); |
soulx | 16:ec0cba3631bc | 810 | if(state == 8) { |
soulx | 16:ec0cba3631bc | 811 | myled=1; |
soulx | 16:ec0cba3631bc | 812 | } else { |
soulx | 16:ec0cba3631bc | 813 | myled=0; |
soulx | 16:ec0cba3631bc | 814 | } |
soulx | 16:ec0cba3631bc | 815 | } else if(status == 1) { |
soulx | 16:ec0cba3631bc | 816 | state =0; |
soulx | 16:ec0cba3631bc | 817 | // sit |
soulx | 16:ec0cba3631bc | 818 | state += leg_left_upper.position_control(d2.left_up); |
soulx | 16:ec0cba3631bc | 819 | state += leg_right_upper.position_control(d2.right_up); |
soulx | 16:ec0cba3631bc | 820 | state += leg_left_lower.position_control(d2.left_down); |
soulx | 16:ec0cba3631bc | 821 | state += leg_right_lower.position_control(d2.right_down); |
soulx | 16:ec0cba3631bc | 822 | if(state == 8) { |
soulx | 16:ec0cba3631bc | 823 | myled=1; |
soulx | 16:ec0cba3631bc | 824 | } else { |
soulx | 16:ec0cba3631bc | 825 | myled=0; |
soulx | 16:ec0cba3631bc | 826 | } |
soulx | 16:ec0cba3631bc | 827 | } |
soulx | 16:ec0cba3631bc | 828 | } |
soulx | 16:ec0cba3631bc | 829 | //t.stop(); |
soulx | 6:8d80c84e0c09 | 830 | } |