![](/media/cache/group/default_image.jpg.50x50_q85.jpg)
CatPot for defence on RoboCup in 2015 winter
Dependencies: AQM0802A HMC6352 MultiSerial PID Servo mbed
main.cpp@0:d35efbf4d62e, 2015-01-24 (annotated)
- Committer:
- lilac0112_1
- Date:
- Sat Jan 24 05:41:05 2015 +0000
- Revision:
- 0:d35efbf4d62e
- Child:
- 1:e3248f278663
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
lilac0112_1 | 0:d35efbf4d62e | 1 | /*********************************** |
lilac0112_1 | 0:d35efbf4d62e | 2 | *RoboCupJunior Soccer B Open 2014 |
lilac0112_1 | 0:d35efbf4d62e | 3 | *Koshinestu progrum |
lilac0112_1 | 0:d35efbf4d62e | 4 | * |
lilac0112_1 | 0:d35efbf4d62e | 5 | *このプログラムでは以下の処理をする. |
lilac0112_1 | 0:d35efbf4d62e | 6 | * LPC1114FN28/102からI2Cを用いて各種センサデータを収集 |
lilac0112_1 | 0:d35efbf4d62e | 7 | * |
lilac0112_1 | 0:d35efbf4d62e | 8 | * データからロボットの移動やキッカー等のモータの動作を決定する処理を行う |
lilac0112_1 | 0:d35efbf4d62e | 9 | * |
lilac0112_1 | 0:d35efbf4d62e | 10 | * MotorDriverにmaxonに命令 |
lilac0112_1 | 0:d35efbf4d62e | 11 | * |
lilac0112_1 | 0:d35efbf4d62e | 12 | * ServoMotorでステアリング |
lilac0112_1 | 0:d35efbf4d62e | 13 | * |
lilac0112_1 | 0:d35efbf4d62e | 14 | * LCDでデバック |
lilac0112_1 | 0:d35efbf4d62e | 15 | * |
lilac0112_1 | 0:d35efbf4d62e | 16 | * スイッチ4つとスタートスイッチで処理を実行 |
lilac0112_1 | 0:d35efbf4d62e | 17 | * |
lilac0112_1 | 0:d35efbf4d62e | 18 | * キッカー用のDigitalOutがどこかに入る |
lilac0112_1 | 0:d35efbf4d62e | 19 | * |
lilac0112_1 | 0:d35efbf4d62e | 20 | ************************* |
lilac0112_1 | 0:d35efbf4d62e | 21 | * |
lilac0112_1 | 0:d35efbf4d62e | 22 | *Pin Map |
lilac0112_1 | 0:d35efbf4d62e | 23 | * |
lilac0112_1 | 0:d35efbf4d62e | 24 | * p5,p6,p7,p29,p30 >> SPI >>Stepping |
lilac0112_1 | 0:d35efbf4d62e | 25 | * |
lilac0112_1 | 0:d35efbf4d62e | 26 | * p9,p10 >> I2C orSerial >> LPC1114FN28/102 read |
lilac0112_1 | 0:d35efbf4d62e | 27 | * |
lilac0112_1 | 0:d35efbf4d62e | 28 | * p13,p14 >> Serial >> Motor |
lilac0112_1 | 0:d35efbf4d62e | 29 | * |
lilac0112_1 | 0:d35efbf4d62e | 30 | * p22~p26 >> DebugSw and StartSw |
lilac0112_1 | 0:d35efbf4d62e | 31 | * |
lilac0112_1 | 0:d35efbf4d62e | 32 | * p27,p28 >> I2C >> DebugLCD |
lilac0112_1 | 0:d35efbf4d62e | 33 | * |
lilac0112_1 | 0:d35efbf4d62e | 34 | * p21 >> ServoMotor |
lilac0112_1 | 0:d35efbf4d62e | 35 | * |
lilac0112_1 | 0:d35efbf4d62e | 36 | ******************************/ |
lilac0112_1 | 0:d35efbf4d62e | 37 | |
lilac0112_1 | 0:d35efbf4d62e | 38 | |
lilac0112_1 | 0:d35efbf4d62e | 39 | /* |
lilac0112_1 | 0:d35efbf4d62e | 40 | |
lilac0112_1 | 0:d35efbf4d62e | 41 | ****以下IRはNighは距離が近いものとする. |
lilac0112_1 | 0:d35efbf4d62e | 42 | |
lilac0112_1 | 0:d35efbf4d62e | 43 | */ |
lilac0112_1 | 0:d35efbf4d62e | 44 | |
lilac0112_1 | 0:d35efbf4d62e | 45 | |
lilac0112_1 | 0:d35efbf4d62e | 46 | |
lilac0112_1 | 0:d35efbf4d62e | 47 | |
lilac0112_1 | 0:d35efbf4d62e | 48 | |
lilac0112_1 | 0:d35efbf4d62e | 49 | |
lilac0112_1 | 0:d35efbf4d62e | 50 | #include "mbed.h" |
lilac0112_1 | 0:d35efbf4d62e | 51 | #include "L6470.h" |
lilac0112_1 | 0:d35efbf4d62e | 52 | #include "PID.h" |
lilac0112_1 | 0:d35efbf4d62e | 53 | #include "AQM0802A.h" |
lilac0112_1 | 0:d35efbf4d62e | 54 | #include "HMC6352.h" |
lilac0112_1 | 0:d35efbf4d62e | 55 | #include "Servo.h" |
lilac0112_1 | 0:d35efbf4d62e | 56 | |
lilac0112_1 | 0:d35efbf4d62e | 57 | #include <math.h> |
lilac0112_1 | 0:d35efbf4d62e | 58 | #include <sstream> |
lilac0112_1 | 0:d35efbf4d62e | 59 | |
lilac0112_1 | 0:d35efbf4d62e | 60 | /*回り込みの計算用*/ |
lilac0112_1 | 0:d35efbf4d62e | 61 | #define PI 3.141593/*割と早めにきってある*/ |
lilac0112_1 | 0:d35efbf4d62e | 62 | #define SHORT_LEN 15 /*cm換算 楕円のB辺の長さを定義しておく*/ |
lilac0112_1 | 0:d35efbf4d62e | 63 | |
lilac0112_1 | 0:d35efbf4d62e | 64 | #define ADDRESS_R 0xA0 |
lilac0112_1 | 0:d35efbf4d62e | 65 | #define ADDRESS_L 0xC0 |
lilac0112_1 | 0:d35efbf4d62e | 66 | |
lilac0112_1 | 0:d35efbf4d62e | 67 | /*BusIn sw 入力値*/ |
lilac0112_1 | 0:d35efbf4d62e | 68 | #define Calibration 0x01 |
lilac0112_1 | 0:d35efbf4d62e | 69 | #define Kicker 0x02 |
lilac0112_1 | 0:d35efbf4d62e | 70 | #define Debug1 0x04 |
lilac0112_1 | 0:d35efbf4d62e | 71 | #define Debug2 0x08 |
lilac0112_1 | 0:d35efbf4d62e | 72 | #define StartS 0x10 |
lilac0112_1 | 0:d35efbf4d62e | 73 | |
lilac0112_1 | 0:d35efbf4d62e | 74 | #define READ_IR 0x01 //送る物指定 |
lilac0112_1 | 0:d35efbf4d62e | 75 | #define READ_PING 0x02 |
lilac0112_1 | 0:d35efbf4d62e | 76 | |
lilac0112_1 | 0:d35efbf4d62e | 77 | /*Servo*/ |
lilac0112_1 | 0:d35efbf4d62e | 78 | #define HOME 0.0 |
lilac0112_1 | 0:d35efbf4d62e | 79 | #define UNIT 360.0 / 12 |
lilac0112_1 | 0:d35efbf4d62e | 80 | #define H1 HOME + 1*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 81 | #define H2 HOME + 2*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 82 | #define H3 HOME + 3*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 83 | #define H4 HOME - 2*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 84 | #define H5 HOME - 1*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 85 | #define H6 HOME |
lilac0112_1 | 0:d35efbf4d62e | 86 | #define H7 HOME + 1*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 87 | #define H8 HOME + 2*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 88 | #define H9 HOME - 3*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 89 | #define H10 HOME - 2*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 90 | #define H11 HOME - 1*UNIT |
lilac0112_1 | 0:d35efbf4d62e | 91 | #define H12 HOME |
lilac0112_1 | 0:d35efbf4d62e | 92 | |
lilac0112_1 | 0:d35efbf4d62e | 93 | #define F90 +90.0 |
lilac0112_1 | 0:d35efbf4d62e | 94 | #define L90 -90.0 |
lilac0112_1 | 0:d35efbf4d62e | 95 | |
lilac0112_1 | 0:d35efbf4d62e | 96 | //ex.) Servo::position(float degrees) |
lilac0112_1 | 0:d35efbf4d62e | 97 | //○ Servo.position(HOME); |
lilac0112_1 | 0:d35efbf4d62e | 98 | //× Servo=HOME; |
lilac0112_1 | 0:d35efbf4d62e | 99 | |
lilac0112_1 | 0:d35efbf4d62e | 100 | BusIn Sw(p22,p23,p24,p25,p26); |
lilac0112_1 | 0:d35efbf4d62e | 101 | DigitalOut Led[4] = {LED1,LED2,LED3,LED4}; |
lilac0112_1 | 0:d35efbf4d62e | 102 | |
lilac0112_1 | 0:d35efbf4d62e | 103 | I2C Sensor(p9,p10);//sda,scl |
lilac0112_1 | 0:d35efbf4d62e | 104 | HMC6352 hmc6352(p9,p10); |
lilac0112_1 | 0:d35efbf4d62e | 105 | AQM0802A Lcd(p28,p27);//sda,scl |
lilac0112_1 | 0:d35efbf4d62e | 106 | L6470 Step(p5,p6,p7,p29,p30);//mosi,miso,sck,#cs,busy(PullUp) |
lilac0112_1 | 0:d35efbf4d62e | 107 | |
lilac0112_1 | 0:d35efbf4d62e | 108 | Servo Servo(NC); |
lilac0112_1 | 0:d35efbf4d62e | 109 | |
lilac0112_1 | 0:d35efbf4d62e | 110 | Serial Motor(p13,p14);//tx,rx |
lilac0112_1 | 0:d35efbf4d62e | 111 | Serial pc(USBTX,USBRX); |
lilac0112_1 | 0:d35efbf4d62e | 112 | |
lilac0112_1 | 0:d35efbf4d62e | 113 | DigitalOut Kick(p21); |
lilac0112_1 | 0:d35efbf4d62e | 114 | |
lilac0112_1 | 0:d35efbf4d62e | 115 | extern string StringFIN; |
lilac0112_1 | 0:d35efbf4d62e | 116 | extern void array(int,int,int,int); |
lilac0112_1 | 0:d35efbf4d62e | 117 | |
lilac0112_1 | 0:d35efbf4d62e | 118 | int speed[4] = {0}; |
lilac0112_1 | 0:d35efbf4d62e | 119 | |
lilac0112_1 | 0:d35efbf4d62e | 120 | typedef enum {FRONT = 1, RIGHT, BACK, LEFT, NA} Direction; |
lilac0112_1 | 0:d35efbf4d62e | 121 | |
lilac0112_1 | 0:d35efbf4d62e | 122 | /*SensorData回収↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓*/ |
lilac0112_1 | 0:d35efbf4d62e | 123 | unsigned int IrReceiveR(){ |
lilac0112_1 | 0:d35efbf4d62e | 124 | /*順位解析版 |
lilac0112_1 | 0:d35efbf4d62e | 125 | Slave側はIRを要求した場合IRのみを返してくるとする. |
lilac0112_1 | 0:d35efbf4d62e | 126 | irは値が大きいほうが近いと仮定する |
lilac0112_1 | 0:d35efbf4d62e | 127 | |
lilac0112_1 | 0:d35efbf4d62e | 128 | |
lilac0112_1 | 0:d35efbf4d62e | 129 | */ |
lilac0112_1 | 0:d35efbf4d62e | 130 | char data_r[3],data_l[3]; |
lilac0112_1 | 0:d35efbf4d62e | 131 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 132 | Sensor.write(READ_IR);//一斉送信のつもり//コンパスへの影響はどのくらいですか |
lilac0112_1 | 0:d35efbf4d62e | 133 | |
lilac0112_1 | 0:d35efbf4d62e | 134 | val = Sensor.read(ADDRESS_R|1, data_r, 3);// IRデータを受信 |
lilac0112_1 | 0:d35efbf4d62e | 135 | Led[0] = val; |
lilac0112_1 | 0:d35efbf4d62e | 136 | wait_ms(5); |
lilac0112_1 | 0:d35efbf4d62e | 137 | val = Sensor.read(ADDRESS_L|1, data_l, 3); |
lilac0112_1 | 0:d35efbf4d62e | 138 | Led[0] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 139 | |
lilac0112_1 | 0:d35efbf4d62e | 140 | if((data_r[0] == 0)||(data_l[0] == 0)){/*ボールを検知しているかチェック*/ |
lilac0112_1 | 0:d35efbf4d62e | 141 | if((data_r[0] == 0)&&(data_l[0] == 0)){ |
lilac0112_1 | 0:d35efbf4d62e | 142 | return 12; |
lilac0112_1 | 0:d35efbf4d62e | 143 | } |
lilac0112_1 | 0:d35efbf4d62e | 144 | if(data_r[0] == 0){ |
lilac0112_1 | 0:d35efbf4d62e | 145 | return (data_l[0]/6+6)*12*12 + (data_l[0]%6+6)*12 + data_r[0]/6; |
lilac0112_1 | 0:d35efbf4d62e | 146 | } |
lilac0112_1 | 0:d35efbf4d62e | 147 | return data_r[0]/6*12*12 + (data_r[0]%6)*12 + data_l[0]/6+6; |
lilac0112_1 | 0:d35efbf4d62e | 148 | |
lilac0112_1 | 0:d35efbf4d62e | 149 | } |
lilac0112_1 | 0:d35efbf4d62e | 150 | |
lilac0112_1 | 0:d35efbf4d62e | 151 | if(data_r[2]>data_l[2]){ |
lilac0112_1 | 0:d35efbf4d62e | 152 | if(data_r[2]>data_l[1]){ |
lilac0112_1 | 0:d35efbf4d62e | 153 | return data_r[0]/6*12*12 + (data_r[0]%6)*12 + data_l[0]/6+6; |
lilac0112_1 | 0:d35efbf4d62e | 154 | } |
lilac0112_1 | 0:d35efbf4d62e | 155 | |
lilac0112_1 | 0:d35efbf4d62e | 156 | return data_r[0]/6*12*12 +(data_l[0]/6+6)*12+ data_r[0]%6; |
lilac0112_1 | 0:d35efbf4d62e | 157 | |
lilac0112_1 | 0:d35efbf4d62e | 158 | }else{ |
lilac0112_1 | 0:d35efbf4d62e | 159 | if(data_l[2]>data_r[1]){ |
lilac0112_1 | 0:d35efbf4d62e | 160 | return (data_l[0]/6+6)*12*12 + (data_l[0]%6+6)*12 + data_r[0]/6; |
lilac0112_1 | 0:d35efbf4d62e | 161 | } |
lilac0112_1 | 0:d35efbf4d62e | 162 | |
lilac0112_1 | 0:d35efbf4d62e | 163 | return (data_l[0]/6+6)*12*12 +(data_r[0]/6)*12+ (data_l[0]%6+6); |
lilac0112_1 | 0:d35efbf4d62e | 164 | } |
lilac0112_1 | 0:d35efbf4d62e | 165 | |
lilac0112_1 | 0:d35efbf4d62e | 166 | } |
lilac0112_1 | 0:d35efbf4d62e | 167 | |
lilac0112_1 | 0:d35efbf4d62e | 168 | uint8_t IrReceiveS(){ |
lilac0112_1 | 0:d35efbf4d62e | 169 | /*単純解析版 一番大きい位置だけ返す |
lilac0112_1 | 0:d35efbf4d62e | 170 | |
lilac0112_1 | 0:d35efbf4d62e | 171 | Slave側はIRを要求した場合IRのみを返してくるとする. |
lilac0112_1 | 0:d35efbf4d62e | 172 | irは値が大きいほうが近いと仮定する |
lilac0112_1 | 0:d35efbf4d62e | 173 | |
lilac0112_1 | 0:d35efbf4d62e | 174 | */ |
lilac0112_1 | 0:d35efbf4d62e | 175 | char data_r[3],data_l[3]; |
lilac0112_1 | 0:d35efbf4d62e | 176 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 177 | Sensor.write(READ_IR);//一斉送信のつもり//コンパスへの影響はどのくらいですか |
lilac0112_1 | 0:d35efbf4d62e | 178 | |
lilac0112_1 | 0:d35efbf4d62e | 179 | val = Sensor.read(ADDRESS_R|1, data_r, 3);// IRデータを受信 |
lilac0112_1 | 0:d35efbf4d62e | 180 | Led[0] = val; |
lilac0112_1 | 0:d35efbf4d62e | 181 | wait_ms(5); |
lilac0112_1 | 0:d35efbf4d62e | 182 | val = Sensor.read(ADDRESS_L|1, data_l, 3); |
lilac0112_1 | 0:d35efbf4d62e | 183 | Led[0] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 184 | |
lilac0112_1 | 0:d35efbf4d62e | 185 | if((data_r[0] == 0)||(data_l[0] == 0)){/*ボールを検知しているかチェック*/ |
lilac0112_1 | 0:d35efbf4d62e | 186 | if((data_r[0] == 0)&&(data_l[0] == 0)){ |
lilac0112_1 | 0:d35efbf4d62e | 187 | return 12; |
lilac0112_1 | 0:d35efbf4d62e | 188 | } |
lilac0112_1 | 0:d35efbf4d62e | 189 | if(data_r[0] == 0){ |
lilac0112_1 | 0:d35efbf4d62e | 190 | return data_l[0]/6+6; |
lilac0112_1 | 0:d35efbf4d62e | 191 | } |
lilac0112_1 | 0:d35efbf4d62e | 192 | return data_r[0]/6; |
lilac0112_1 | 0:d35efbf4d62e | 193 | } |
lilac0112_1 | 0:d35efbf4d62e | 194 | |
lilac0112_1 | 0:d35efbf4d62e | 195 | if(data_r[2]>data_l[2]){ |
lilac0112_1 | 0:d35efbf4d62e | 196 | return data_r[0]/6; |
lilac0112_1 | 0:d35efbf4d62e | 197 | } |
lilac0112_1 | 0:d35efbf4d62e | 198 | return data_l[0]/6+6; |
lilac0112_1 | 0:d35efbf4d62e | 199 | |
lilac0112_1 | 0:d35efbf4d62e | 200 | } |
lilac0112_1 | 0:d35efbf4d62e | 201 | uint8_t IrReceiveM(){ |
lilac0112_1 | 0:d35efbf4d62e | 202 | /*値解析版 一番近い場所の値を返す(位置はとりあえずない) |
lilac0112_1 | 0:d35efbf4d62e | 203 | Slave側はIRを要求した場合IRのみを返してくるとする. |
lilac0112_1 | 0:d35efbf4d62e | 204 | irは値が大きいほうが近いと仮定する |
lilac0112_1 | 0:d35efbf4d62e | 205 | |
lilac0112_1 | 0:d35efbf4d62e | 206 | |
lilac0112_1 | 0:d35efbf4d62e | 207 | */ |
lilac0112_1 | 0:d35efbf4d62e | 208 | char data_r[3],data_l[3]; |
lilac0112_1 | 0:d35efbf4d62e | 209 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 210 | Sensor.write(READ_IR);//一斉送信のつもり//コンパスへの影響はどのくらいですか |
lilac0112_1 | 0:d35efbf4d62e | 211 | |
lilac0112_1 | 0:d35efbf4d62e | 212 | val = Sensor.read(ADDRESS_R|1, data_r, 3);// IRデータを受信 |
lilac0112_1 | 0:d35efbf4d62e | 213 | Led[0] = val; |
lilac0112_1 | 0:d35efbf4d62e | 214 | wait_ms(5); |
lilac0112_1 | 0:d35efbf4d62e | 215 | val = Sensor.read(ADDRESS_L|1, data_l, 3); |
lilac0112_1 | 0:d35efbf4d62e | 216 | Led[0] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 217 | |
lilac0112_1 | 0:d35efbf4d62e | 218 | if((data_r[0] == 0)||(data_l[0] == 0)){/*ボールを検知しているかチェック*/ |
lilac0112_1 | 0:d35efbf4d62e | 219 | if((data_r[0] == 0)&&(data_l[0] == 0)){ |
lilac0112_1 | 0:d35efbf4d62e | 220 | return 255; |
lilac0112_1 | 0:d35efbf4d62e | 221 | } |
lilac0112_1 | 0:d35efbf4d62e | 222 | if(data_r[0] == 0){ |
lilac0112_1 | 0:d35efbf4d62e | 223 | return data_l[1]; |
lilac0112_1 | 0:d35efbf4d62e | 224 | } |
lilac0112_1 | 0:d35efbf4d62e | 225 | return data_r[1]; |
lilac0112_1 | 0:d35efbf4d62e | 226 | } |
lilac0112_1 | 0:d35efbf4d62e | 227 | |
lilac0112_1 | 0:d35efbf4d62e | 228 | |
lilac0112_1 | 0:d35efbf4d62e | 229 | if(data_r[2]>data_l[2]){ |
lilac0112_1 | 0:d35efbf4d62e | 230 | return data_r[1]; |
lilac0112_1 | 0:d35efbf4d62e | 231 | |
lilac0112_1 | 0:d35efbf4d62e | 232 | } |
lilac0112_1 | 0:d35efbf4d62e | 233 | |
lilac0112_1 | 0:d35efbf4d62e | 234 | return data_l[1]; |
lilac0112_1 | 0:d35efbf4d62e | 235 | |
lilac0112_1 | 0:d35efbf4d62e | 236 | } |
lilac0112_1 | 0:d35efbf4d62e | 237 | unsigned int IrReceiveSM(){//16bit() |
lilac0112_1 | 0:d35efbf4d62e | 238 | /*値解析版 一番大きい値とその位置を返す |
lilac0112_1 | 0:d35efbf4d62e | 239 | Slave側はIRを要求した場合IRのみを返してくるとする. |
lilac0112_1 | 0:d35efbf4d62e | 240 | irは値が大きいほうが近いと仮定する |
lilac0112_1 | 0:d35efbf4d62e | 241 | |
lilac0112_1 | 0:d35efbf4d62e | 242 | |
lilac0112_1 | 0:d35efbf4d62e | 243 | */ |
lilac0112_1 | 0:d35efbf4d62e | 244 | char data_r[3],data_l[3]; |
lilac0112_1 | 0:d35efbf4d62e | 245 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 246 | Sensor.write(READ_IR);//一斉送信のつもり//コンパスへの影響はどのくらいですか |
lilac0112_1 | 0:d35efbf4d62e | 247 | |
lilac0112_1 | 0:d35efbf4d62e | 248 | val = Sensor.read(ADDRESS_R|1, data_r, 3);// IRデータを受信 |
lilac0112_1 | 0:d35efbf4d62e | 249 | Led[0] = val; |
lilac0112_1 | 0:d35efbf4d62e | 250 | wait_ms(5); |
lilac0112_1 | 0:d35efbf4d62e | 251 | val = Sensor.read(ADDRESS_L|1, data_l, 3); |
lilac0112_1 | 0:d35efbf4d62e | 252 | Led[0] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 253 | |
lilac0112_1 | 0:d35efbf4d62e | 254 | if((data_r[0] == 0)||(data_l[0] == 0)){/*ボールを検知しているかチェック*/ |
lilac0112_1 | 0:d35efbf4d62e | 255 | if((data_r[0] == 0)&&(data_l[0] == 0)){ |
lilac0112_1 | 0:d35efbf4d62e | 256 | return 12<<8+255; |
lilac0112_1 | 0:d35efbf4d62e | 257 | } |
lilac0112_1 | 0:d35efbf4d62e | 258 | if(data_r[0] == 0){ |
lilac0112_1 | 0:d35efbf4d62e | 259 | return (data_l[0]/6+6)<<8 + data_l[1]; |
lilac0112_1 | 0:d35efbf4d62e | 260 | } |
lilac0112_1 | 0:d35efbf4d62e | 261 | return data_r[0]/6<<8 + data_r[1]; |
lilac0112_1 | 0:d35efbf4d62e | 262 | } |
lilac0112_1 | 0:d35efbf4d62e | 263 | |
lilac0112_1 | 0:d35efbf4d62e | 264 | |
lilac0112_1 | 0:d35efbf4d62e | 265 | if(data_r[2]>data_l[2]){ |
lilac0112_1 | 0:d35efbf4d62e | 266 | return data_r[0]/6<<8 + data_r[1]; |
lilac0112_1 | 0:d35efbf4d62e | 267 | |
lilac0112_1 | 0:d35efbf4d62e | 268 | } |
lilac0112_1 | 0:d35efbf4d62e | 269 | return ((data_l[0]/6)+6) <<8 + data_l[1]; |
lilac0112_1 | 0:d35efbf4d62e | 270 | |
lilac0112_1 | 0:d35efbf4d62e | 271 | |
lilac0112_1 | 0:d35efbf4d62e | 272 | } |
lilac0112_1 | 0:d35efbf4d62e | 273 | uint8_t LineReceive(){ |
lilac0112_1 | 0:d35efbf4d62e | 274 | //先に要求しない場合はLineの状況を送信すること.//4bit //前ー右ー後ろー左 |
lilac0112_1 | 0:d35efbf4d62e | 275 | char data_r[2],data_l[2]; |
lilac0112_1 | 0:d35efbf4d62e | 276 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 277 | //example val = slave.read(address,data,length,repeat); |
lilac0112_1 | 0:d35efbf4d62e | 278 | val = Sensor.read(ADDRESS_R|1, data_r, 1); |
lilac0112_1 | 0:d35efbf4d62e | 279 | Led[1] = val; |
lilac0112_1 | 0:d35efbf4d62e | 280 | wait_ms(5); |
lilac0112_1 | 0:d35efbf4d62e | 281 | val = Sensor.read(ADDRESS_L|1, data_l, 1); |
lilac0112_1 | 0:d35efbf4d62e | 282 | Led[1] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 283 | |
lilac0112_1 | 0:d35efbf4d62e | 284 | |
lilac0112_1 | 0:d35efbf4d62e | 285 | return data_r[0]<<2 + data_l[0]; |
lilac0112_1 | 0:d35efbf4d62e | 286 | |
lilac0112_1 | 0:d35efbf4d62e | 287 | |
lilac0112_1 | 0:d35efbf4d62e | 288 | } |
lilac0112_1 | 0:d35efbf4d62e | 289 | |
lilac0112_1 | 0:d35efbf4d62e | 290 | |
lilac0112_1 | 0:d35efbf4d62e | 291 | void PingReceiveRL(char ping[]){//ping[0]==Right,ping[1]==Left |
lilac0112_1 | 0:d35efbf4d62e | 292 | char ReadSelect[1] = {READ_PING}; |
lilac0112_1 | 0:d35efbf4d62e | 293 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 294 | val = Sensor.write(ADDRESS_R|0, ReadSelect , 1); |
lilac0112_1 | 0:d35efbf4d62e | 295 | Led[2] = val; |
lilac0112_1 | 0:d35efbf4d62e | 296 | val = Sensor.read(ADDRESS_R|1, ping, 2); |
lilac0112_1 | 0:d35efbf4d62e | 297 | Led[2] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 298 | |
lilac0112_1 | 0:d35efbf4d62e | 299 | |
lilac0112_1 | 0:d35efbf4d62e | 300 | } |
lilac0112_1 | 0:d35efbf4d62e | 301 | |
lilac0112_1 | 0:d35efbf4d62e | 302 | void PingReceiveFB(char ping[]){//ping[0]==FRONT,ping[1]==BACK |
lilac0112_1 | 0:d35efbf4d62e | 303 | char ReadSelect[1] = {READ_PING}; |
lilac0112_1 | 0:d35efbf4d62e | 304 | bool val; |
lilac0112_1 | 0:d35efbf4d62e | 305 | val = Sensor.write(ADDRESS_L|0, ReadSelect , 1); |
lilac0112_1 | 0:d35efbf4d62e | 306 | Led[2] = val; |
lilac0112_1 | 0:d35efbf4d62e | 307 | val = Sensor.read(ADDRESS_L|1, ping, 2); |
lilac0112_1 | 0:d35efbf4d62e | 308 | Led[2] = !val; |
lilac0112_1 | 0:d35efbf4d62e | 309 | |
lilac0112_1 | 0:d35efbf4d62e | 310 | |
lilac0112_1 | 0:d35efbf4d62e | 311 | } |
lilac0112_1 | 0:d35efbf4d62e | 312 | |
lilac0112_1 | 0:d35efbf4d62e | 313 | /*SensorData回収↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑*/ |
lilac0112_1 | 0:d35efbf4d62e | 314 | |
lilac0112_1 | 0:d35efbf4d62e | 315 | /*モーター駆動処理↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓*/ |
lilac0112_1 | 0:d35efbf4d62e | 316 | |
lilac0112_1 | 0:d35efbf4d62e | 317 | void rotate(unsigned int times, bool dir){ |
lilac0112_1 | 0:d35efbf4d62e | 318 | /* |
lilac0112_1 | 0:d35efbf4d62e | 319 | *回転速度,回転方向,回転角度等設定変更ののち回転. |
lilac0112_1 | 0:d35efbf4d62e | 320 | * this is 使わなそうである、 |
lilac0112_1 | 0:d35efbf4d62e | 321 | */ |
lilac0112_1 | 0:d35efbf4d62e | 322 | |
lilac0112_1 | 0:d35efbf4d62e | 323 | |
lilac0112_1 | 0:d35efbf4d62e | 324 | |
lilac0112_1 | 0:d35efbf4d62e | 325 | |
lilac0112_1 | 0:d35efbf4d62e | 326 | |
lilac0112_1 | 0:d35efbf4d62e | 327 | } |
lilac0112_1 | 0:d35efbf4d62e | 328 | |
lilac0112_1 | 0:d35efbf4d62e | 329 | void move(int vr, int vl){ |
lilac0112_1 | 0:d35efbf4d62e | 330 | double pwm[4] = {0}; |
lilac0112_1 | 0:d35efbf4d62e | 331 | uint8_t i = 0; |
lilac0112_1 | 0:d35efbf4d62e | 332 | pwm[0] = vr/10.0; |
lilac0112_1 | 0:d35efbf4d62e | 333 | pwm[1] = vl/10.0; |
lilac0112_1 | 0:d35efbf4d62e | 334 | pwm[2] = 0; |
lilac0112_1 | 0:d35efbf4d62e | 335 | pwm[3] = 0; |
lilac0112_1 | 0:d35efbf4d62e | 336 | |
lilac0112_1 | 0:d35efbf4d62e | 337 | for(i = 0; i < 4; i++){ |
lilac0112_1 | 0:d35efbf4d62e | 338 | if(pwm[i] > 100){ |
lilac0112_1 | 0:d35efbf4d62e | 339 | pwm[i] = 100; |
lilac0112_1 | 0:d35efbf4d62e | 340 | }else if(pwm[i] < -100){ |
lilac0112_1 | 0:d35efbf4d62e | 341 | pwm[i] = -100; |
lilac0112_1 | 0:d35efbf4d62e | 342 | } |
lilac0112_1 | 0:d35efbf4d62e | 343 | speed[i] = pwm[i]; |
lilac0112_1 | 0:d35efbf4d62e | 344 | } |
lilac0112_1 | 0:d35efbf4d62e | 345 | } |
lilac0112_1 | 0:d35efbf4d62e | 346 | |
lilac0112_1 | 0:d35efbf4d62e | 347 | void ControlRobo0(int *CompassDef)//LeftFront 11時 |
lilac0112_1 | 0:d35efbf4d62e | 348 | {} |
lilac0112_1 | 0:d35efbf4d62e | 349 | void ControlRobo1(int *CompassDef)//Front 12時 |
lilac0112_1 | 0:d35efbf4d62e | 350 | { |
lilac0112_1 | 0:d35efbf4d62e | 351 | /*前にボールがある場合の動作*/ |
lilac0112_1 | 0:d35efbf4d62e | 352 | int Compass; |
lilac0112_1 | 0:d35efbf4d62e | 353 | char Ping[2]; |
lilac0112_1 | 0:d35efbf4d62e | 354 | uint8_t Line,LineIr; |
lilac0112_1 | 0:d35efbf4d62e | 355 | unsigned int IrNumMax; |
lilac0112_1 | 0:d35efbf4d62e | 356 | |
lilac0112_1 | 0:d35efbf4d62e | 357 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 358 | if(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 359 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 360 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 361 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 362 | } |
lilac0112_1 | 0:d35efbf4d62e | 363 | return; |
lilac0112_1 | 0:d35efbf4d62e | 364 | } |
lilac0112_1 | 0:d35efbf4d62e | 365 | if(IrReceiveM()<=150){//適当な150 |
lilac0112_1 | 0:d35efbf4d62e | 366 | /*ステッピングを正面に設定*/ |
lilac0112_1 | 0:d35efbf4d62e | 367 | /*busy_wait()*/ |
lilac0112_1 | 0:d35efbf4d62e | 368 | /*モーターを前進*/ |
lilac0112_1 | 0:d35efbf4d62e | 369 | return; |
lilac0112_1 | 0:d35efbf4d62e | 370 | } |
lilac0112_1 | 0:d35efbf4d62e | 371 | PingReceiveRL(Ping); |
lilac0112_1 | 0:d35efbf4d62e | 372 | if((Ping[0]>90)&&(Ping[1]>40)){//数値は適当 |
lilac0112_1 | 0:d35efbf4d62e | 373 | /*ステッピングを少しだけ傾ける*/ |
lilac0112_1 | 0:d35efbf4d62e | 374 | /*モーターを左右差つけて回す(ロボットは少し傾く)*/ |
lilac0112_1 | 0:d35efbf4d62e | 375 | /*busy_wait()*/ |
lilac0112_1 | 0:d35efbf4d62e | 376 | /*モーターを前進*/ |
lilac0112_1 | 0:d35efbf4d62e | 377 | while(1){ |
lilac0112_1 | 0:d35efbf4d62e | 378 | Line = LineReceive(); |
lilac0112_1 | 0:d35efbf4d62e | 379 | |
lilac0112_1 | 0:d35efbf4d62e | 380 | if(Line){ //ラインを検知していないか |
lilac0112_1 | 0:d35efbf4d62e | 381 | LineIr = Line & (IrReceiveS()/3 + 1);//計算により方位を合わせる。 |
lilac0112_1 | 0:d35efbf4d62e | 382 | while(LineIr){ |
lilac0112_1 | 0:d35efbf4d62e | 383 | move(0,0);// |
lilac0112_1 | 0:d35efbf4d62e | 384 | Led[1] = Led[2] = Led[3] = 1; |
lilac0112_1 | 0:d35efbf4d62e | 385 | |
lilac0112_1 | 0:d35efbf4d62e | 386 | LineIr = LineReceive() & (IrReceiveS()/3 + 1); |
lilac0112_1 | 0:d35efbf4d62e | 387 | } |
lilac0112_1 | 0:d35efbf4d62e | 388 | Led[1] = Led[2] = Led[3] = 0; |
lilac0112_1 | 0:d35efbf4d62e | 389 | |
lilac0112_1 | 0:d35efbf4d62e | 390 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 391 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 392 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 393 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 394 | } |
lilac0112_1 | 0:d35efbf4d62e | 395 | return; |
lilac0112_1 | 0:d35efbf4d62e | 396 | } |
lilac0112_1 | 0:d35efbf4d62e | 397 | Kick = 1; |
lilac0112_1 | 0:d35efbf4d62e | 398 | wait_ms(200); |
lilac0112_1 | 0:d35efbf4d62e | 399 | Kick = 0; |
lilac0112_1 | 0:d35efbf4d62e | 400 | |
lilac0112_1 | 0:d35efbf4d62e | 401 | IrNumMax = IrReceiveSM();//位置と大きさ |
lilac0112_1 | 0:d35efbf4d62e | 402 | |
lilac0112_1 | 0:d35efbf4d62e | 403 | if(!((IrNumMax&0x00)>>8) == 1){//この1はボールの関数の1を表す. |
lilac0112_1 | 0:d35efbf4d62e | 404 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 405 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 406 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 407 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 408 | } |
lilac0112_1 | 0:d35efbf4d62e | 409 | return; |
lilac0112_1 | 0:d35efbf4d62e | 410 | } |
lilac0112_1 | 0:d35efbf4d62e | 411 | |
lilac0112_1 | 0:d35efbf4d62e | 412 | if((IrNumMax&0x00FF)<150){ |
lilac0112_1 | 0:d35efbf4d62e | 413 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 414 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 415 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 416 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 417 | } |
lilac0112_1 | 0:d35efbf4d62e | 418 | return; |
lilac0112_1 | 0:d35efbf4d62e | 419 | } |
lilac0112_1 | 0:d35efbf4d62e | 420 | |
lilac0112_1 | 0:d35efbf4d62e | 421 | } |
lilac0112_1 | 0:d35efbf4d62e | 422 | |
lilac0112_1 | 0:d35efbf4d62e | 423 | }else if((Ping[0]>40)&&(Ping[1]>90)){ |
lilac0112_1 | 0:d35efbf4d62e | 424 | |
lilac0112_1 | 0:d35efbf4d62e | 425 | }else{ |
lilac0112_1 | 0:d35efbf4d62e | 426 | |
lilac0112_1 | 0:d35efbf4d62e | 427 | } |
lilac0112_1 | 0:d35efbf4d62e | 428 | |
lilac0112_1 | 0:d35efbf4d62e | 429 | } |
lilac0112_1 | 0:d35efbf4d62e | 430 | void ControlRobo2(int *CompassDef)//RightFront 1時 |
lilac0112_1 | 0:d35efbf4d62e | 431 | { |
lilac0112_1 | 0:d35efbf4d62e | 432 | |
lilac0112_1 | 0:d35efbf4d62e | 433 | int Compass; |
lilac0112_1 | 0:d35efbf4d62e | 434 | char Ir[2] ={0};//1, 1,2位, 1位の大きさ |
lilac0112_1 | 0:d35efbf4d62e | 435 | char ir_num,line;//わかりやすい名前 |
lilac0112_1 | 0:d35efbf4d62e | 436 | |
lilac0112_1 | 0:d35efbf4d62e | 437 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 438 | if(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 439 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 440 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 441 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 442 | } |
lilac0112_1 | 0:d35efbf4d62e | 443 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 444 | return; |
lilac0112_1 | 0:d35efbf4d62e | 445 | } |
lilac0112_1 | 0:d35efbf4d62e | 446 | Step.GoHome(); |
lilac0112_1 | 0:d35efbf4d62e | 447 | /*irデータ取得 1,2位の場所、一位の距離*/ |
lilac0112_1 | 0:d35efbf4d62e | 448 | if(!(Ir[0]%13 ==2)){ |
lilac0112_1 | 0:d35efbf4d62e | 449 | return; |
lilac0112_1 | 0:d35efbf4d62e | 450 | } |
lilac0112_1 | 0:d35efbf4d62e | 451 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 452 | |
lilac0112_1 | 0:d35efbf4d62e | 453 | if(Ir[1]>=100){//近い場合 |
lilac0112_1 | 0:d35efbf4d62e | 454 | //2位を含んだ計算 |
lilac0112_1 | 0:d35efbf4d62e | 455 | /*motorset*/ |
lilac0112_1 | 0:d35efbf4d62e | 456 | /*stepset*/ |
lilac0112_1 | 0:d35efbf4d62e | 457 | return; |
lilac0112_1 | 0:d35efbf4d62e | 458 | } |
lilac0112_1 | 0:d35efbf4d62e | 459 | |
lilac0112_1 | 0:d35efbf4d62e | 460 | /*2位を含んだ計算*/ |
lilac0112_1 | 0:d35efbf4d62e | 461 | /*計算された分stepmove*/ |
lilac0112_1 | 0:d35efbf4d62e | 462 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 463 | move(20,20); |
lilac0112_1 | 0:d35efbf4d62e | 464 | |
lilac0112_1 | 0:d35efbf4d62e | 465 | |
lilac0112_1 | 0:d35efbf4d62e | 466 | /*line,ir get*/ |
lilac0112_1 | 0:d35efbf4d62e | 467 | do{ |
lilac0112_1 | 0:d35efbf4d62e | 468 | if(line){ |
lilac0112_1 | 0:d35efbf4d62e | 469 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 470 | return; |
lilac0112_1 | 0:d35efbf4d62e | 471 | } |
lilac0112_1 | 0:d35efbf4d62e | 472 | |
lilac0112_1 | 0:d35efbf4d62e | 473 | /*line,ir get*/ |
lilac0112_1 | 0:d35efbf4d62e | 474 | }while(ir_num == 2); |
lilac0112_1 | 0:d35efbf4d62e | 475 | |
lilac0112_1 | 0:d35efbf4d62e | 476 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 477 | |
lilac0112_1 | 0:d35efbf4d62e | 478 | |
lilac0112_1 | 0:d35efbf4d62e | 479 | |
lilac0112_1 | 0:d35efbf4d62e | 480 | } |
lilac0112_1 | 0:d35efbf4d62e | 481 | void ControlRobo3(int *CompassDef)//RightFront 2時 |
lilac0112_1 | 0:d35efbf4d62e | 482 | { |
lilac0112_1 | 0:d35efbf4d62e | 483 | int Compass; |
lilac0112_1 | 0:d35efbf4d62e | 484 | char Ir[2] ={0};//1, 1,2位, 1位の大きさ |
lilac0112_1 | 0:d35efbf4d62e | 485 | char ir_num,line;//わかりやすい名前 |
lilac0112_1 | 0:d35efbf4d62e | 486 | |
lilac0112_1 | 0:d35efbf4d62e | 487 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 488 | if(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 489 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 490 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 491 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 492 | } |
lilac0112_1 | 0:d35efbf4d62e | 493 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 494 | return; |
lilac0112_1 | 0:d35efbf4d62e | 495 | } |
lilac0112_1 | 0:d35efbf4d62e | 496 | Step.GoHome(); |
lilac0112_1 | 0:d35efbf4d62e | 497 | /*irデータ取得 1,2位の場所、一位の距離*/ |
lilac0112_1 | 0:d35efbf4d62e | 498 | if(!(Ir[0]%13 ==3)){ |
lilac0112_1 | 0:d35efbf4d62e | 499 | return; |
lilac0112_1 | 0:d35efbf4d62e | 500 | } |
lilac0112_1 | 0:d35efbf4d62e | 501 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 502 | |
lilac0112_1 | 0:d35efbf4d62e | 503 | if(Ir[1] >= 100){ |
lilac0112_1 | 0:d35efbf4d62e | 504 | /*2位を含めた計算*/ |
lilac0112_1 | 0:d35efbf4d62e | 505 | /*move()*/ |
lilac0112_1 | 0:d35efbf4d62e | 506 | /*Stepset*/ |
lilac0112_1 | 0:d35efbf4d62e | 507 | return; |
lilac0112_1 | 0:d35efbf4d62e | 508 | } |
lilac0112_1 | 0:d35efbf4d62e | 509 | /*2位を含めた計算*/ |
lilac0112_1 | 0:d35efbf4d62e | 510 | /*Stepsetting 距離等により角度が変わる*/ |
lilac0112_1 | 0:d35efbf4d62e | 511 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 512 | move(-20,-20); |
lilac0112_1 | 0:d35efbf4d62e | 513 | /*ir,line check*/ |
lilac0112_1 | 0:d35efbf4d62e | 514 | do{ |
lilac0112_1 | 0:d35efbf4d62e | 515 | if(line){ |
lilac0112_1 | 0:d35efbf4d62e | 516 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 517 | return; |
lilac0112_1 | 0:d35efbf4d62e | 518 | } |
lilac0112_1 | 0:d35efbf4d62e | 519 | /*line,ir check*/ |
lilac0112_1 | 0:d35efbf4d62e | 520 | }while(ir_num == 3); |
lilac0112_1 | 0:d35efbf4d62e | 521 | |
lilac0112_1 | 0:d35efbf4d62e | 522 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 523 | |
lilac0112_1 | 0:d35efbf4d62e | 524 | |
lilac0112_1 | 0:d35efbf4d62e | 525 | } |
lilac0112_1 | 0:d35efbf4d62e | 526 | void ControlRobo4(int *CompassDef)//Right 3時 |
lilac0112_1 | 0:d35efbf4d62e | 527 | { |
lilac0112_1 | 0:d35efbf4d62e | 528 | int a = 50; |
lilac0112_1 | 0:d35efbf4d62e | 529 | unsigned int ir_sm; |
lilac0112_1 | 0:d35efbf4d62e | 530 | int kakudo = -90; |
lilac0112_1 | 0:d35efbf4d62e | 531 | double value = 0; |
lilac0112_1 | 0:d35efbf4d62e | 532 | double v = 50;/* cm/s */ |
lilac0112_1 | 0:d35efbf4d62e | 533 | double x = 20;/*モーターを回す割合,今は適当*/ |
lilac0112_1 | 0:d35efbf4d62e | 534 | |
lilac0112_1 | 0:d35efbf4d62e | 535 | ir_sm = IrReceiveSM(); |
lilac0112_1 | 0:d35efbf4d62e | 536 | if(ir_sm&0xF00>>8 == 4){ |
lilac0112_1 | 0:d35efbf4d62e | 537 | return; |
lilac0112_1 | 0:d35efbf4d62e | 538 | } |
lilac0112_1 | 0:d35efbf4d62e | 539 | a = 300 - ir_sm&0x00FF ;//適当な計算//300は勘 |
lilac0112_1 | 0:d35efbf4d62e | 540 | value = 10 * a * SHORT_LEN + 3*(a * a + SHORT_LEN * SHORT_LEN); |
lilac0112_1 | 0:d35efbf4d62e | 541 | value = PI *(3 * ( a + SHORT_LEN) - sqrt(value))/4/v; |
lilac0112_1 | 0:d35efbf4d62e | 542 | |
lilac0112_1 | 0:d35efbf4d62e | 543 | if(300 - ir_sm&0x00FF >200){ |
lilac0112_1 | 0:d35efbf4d62e | 544 | Step.Step(-10);//適当 |
lilac0112_1 | 0:d35efbf4d62e | 545 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 546 | } |
lilac0112_1 | 0:d35efbf4d62e | 547 | |
lilac0112_1 | 0:d35efbf4d62e | 548 | /*SetPerm() |
lilac0112_1 | 0:d35efbf4d62e | 549 | *valueに応じた何かを計算する |
lilac0112_1 | 0:d35efbf4d62e | 550 | *ACCまたはMAX_SPEEDをいじればいい気がする |
lilac0112_1 | 0:d35efbf4d62e | 551 | * |
lilac0112_1 | 0:d35efbf4d62e | 552 | */ |
lilac0112_1 | 0:d35efbf4d62e | 553 | Step.Step(kakudo+10); |
lilac0112_1 | 0:d35efbf4d62e | 554 | |
lilac0112_1 | 0:d35efbf4d62e | 555 | /*x = v*何か*/ |
lilac0112_1 | 0:d35efbf4d62e | 556 | move(-x,-x); |
lilac0112_1 | 0:d35efbf4d62e | 557 | |
lilac0112_1 | 0:d35efbf4d62e | 558 | |
lilac0112_1 | 0:d35efbf4d62e | 559 | } |
lilac0112_1 | 0:d35efbf4d62e | 560 | void ControlRobo5(int *CompassDef)//RightBack 4時 |
lilac0112_1 | 0:d35efbf4d62e | 561 | { |
lilac0112_1 | 0:d35efbf4d62e | 562 | int Compass; |
lilac0112_1 | 0:d35efbf4d62e | 563 | char Ir[2] ={0};//1, 1,2位, 1位の大きさ |
lilac0112_1 | 0:d35efbf4d62e | 564 | char ir_num,line;//わかりやすい名前 |
lilac0112_1 | 0:d35efbf4d62e | 565 | |
lilac0112_1 | 0:d35efbf4d62e | 566 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 567 | if(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 568 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 569 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 570 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 571 | } |
lilac0112_1 | 0:d35efbf4d62e | 572 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 573 | return; |
lilac0112_1 | 0:d35efbf4d62e | 574 | } |
lilac0112_1 | 0:d35efbf4d62e | 575 | Servo.position(HOME); |
lilac0112_1 | 0:d35efbf4d62e | 576 | |
lilac0112_1 | 0:d35efbf4d62e | 577 | /*irデータ取得 1,2位の場所、一位の距離*/ |
lilac0112_1 | 0:d35efbf4d62e | 578 | if(!(Ir[0]%13 == 5)){ |
lilac0112_1 | 0:d35efbf4d62e | 579 | return; |
lilac0112_1 | 0:d35efbf4d62e | 580 | } |
lilac0112_1 | 0:d35efbf4d62e | 581 | |
lilac0112_1 | 0:d35efbf4d62e | 582 | |
lilac0112_1 | 0:d35efbf4d62e | 583 | if(Ir[1] >=100){//近い |
lilac0112_1 | 0:d35efbf4d62e | 584 | /*計算*/ |
lilac0112_1 | 0:d35efbf4d62e | 585 | |
lilac0112_1 | 0:d35efbf4d62e | 586 | Servo.position(H1); |
lilac0112_1 | 0:d35efbf4d62e | 587 | move(-20,-20); |
lilac0112_1 | 0:d35efbf4d62e | 588 | /*Step.setpaaa |
lilac0112_1 | 0:d35efbf4d62e | 589 | Step.move();-180+初期位置 |
lilac0112_1 | 0:d35efbf4d62e | 590 | */ |
lilac0112_1 | 0:d35efbf4d62e | 591 | /*ir,linecheck*/ |
lilac0112_1 | 0:d35efbf4d62e | 592 | do{ |
lilac0112_1 | 0:d35efbf4d62e | 593 | if(line){ |
lilac0112_1 | 0:d35efbf4d62e | 594 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 595 | return; |
lilac0112_1 | 0:d35efbf4d62e | 596 | } |
lilac0112_1 | 0:d35efbf4d62e | 597 | if(!(ir_num >1 && ir_num <=5)){ |
lilac0112_1 | 0:d35efbf4d62e | 598 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 599 | return; |
lilac0112_1 | 0:d35efbf4d62e | 600 | } |
lilac0112_1 | 0:d35efbf4d62e | 601 | /*ir,line check*/ |
lilac0112_1 | 0:d35efbf4d62e | 602 | }while(1); |
lilac0112_1 | 0:d35efbf4d62e | 603 | } |
lilac0112_1 | 0:d35efbf4d62e | 604 | //遠い |
lilac0112_1 | 0:d35efbf4d62e | 605 | |
lilac0112_1 | 0:d35efbf4d62e | 606 | /*計算*/ |
lilac0112_1 | 0:d35efbf4d62e | 607 | |
lilac0112_1 | 0:d35efbf4d62e | 608 | Servo.position(H4); |
lilac0112_1 | 0:d35efbf4d62e | 609 | |
lilac0112_1 | 0:d35efbf4d62e | 610 | move(-20,-20); |
lilac0112_1 | 0:d35efbf4d62e | 611 | |
lilac0112_1 | 0:d35efbf4d62e | 612 | /*ir,linecheck*/ |
lilac0112_1 | 0:d35efbf4d62e | 613 | do{ |
lilac0112_1 | 0:d35efbf4d62e | 614 | if(line){ |
lilac0112_1 | 0:d35efbf4d62e | 615 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 616 | return; |
lilac0112_1 | 0:d35efbf4d62e | 617 | } |
lilac0112_1 | 0:d35efbf4d62e | 618 | if(!(ir_num >1 && ir_num <=5)){ |
lilac0112_1 | 0:d35efbf4d62e | 619 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 620 | } |
lilac0112_1 | 0:d35efbf4d62e | 621 | /*ir,line check*/ |
lilac0112_1 | 0:d35efbf4d62e | 622 | }while(1); |
lilac0112_1 | 0:d35efbf4d62e | 623 | |
lilac0112_1 | 0:d35efbf4d62e | 624 | |
lilac0112_1 | 0:d35efbf4d62e | 625 | } |
lilac0112_1 | 0:d35efbf4d62e | 626 | void ControlRobo6(int *CompassDef)//BackRight 5時 |
lilac0112_1 | 0:d35efbf4d62e | 627 | { |
lilac0112_1 | 0:d35efbf4d62e | 628 | |
lilac0112_1 | 0:d35efbf4d62e | 629 | |
lilac0112_1 | 0:d35efbf4d62e | 630 | } |
lilac0112_1 | 0:d35efbf4d62e | 631 | void ControlRobo7(int *CompassDef)//Back 6時 |
lilac0112_1 | 0:d35efbf4d62e | 632 | { |
lilac0112_1 | 0:d35efbf4d62e | 633 | /***** |
lilac0112_1 | 0:d35efbf4d62e | 634 | * this function is drawing a semicircle. |
lilac0112_1 | 0:d35efbf4d62e | 635 | * semicircle manipulated ir_data&ping_data. |
lilac0112_1 | 0:d35efbf4d62e | 636 | * |
lilac0112_1 | 0:d35efbf4d62e | 637 | * 変数名は後から変えるためにわかりやすい名前にしておく |
lilac0112_1 | 0:d35efbf4d62e | 638 | **/ |
lilac0112_1 | 0:d35efbf4d62e | 639 | uint8_t ir_num; |
lilac0112_1 | 0:d35efbf4d62e | 640 | uint8_t pingl,pingr; |
lilac0112_1 | 0:d35efbf4d62e | 641 | |
lilac0112_1 | 0:d35efbf4d62e | 642 | /* |
lilac0112_1 | 0:d35efbf4d62e | 643 | ir(1位,2位,必要なら距離も)と超音波のデータを取得 |
lilac0112_1 | 0:d35efbf4d62e | 644 | */ |
lilac0112_1 | 0:d35efbf4d62e | 645 | if(ir_num==7){//一致しているかどうか念のため |
lilac0112_1 | 0:d35efbf4d62e | 646 | return ; |
lilac0112_1 | 0:d35efbf4d62e | 647 | } |
lilac0112_1 | 0:d35efbf4d62e | 648 | if(pingr<pingl){//本当ならば壁と垂直かどうか、確認すべき。コンパスや超音波の合計を見れば可能 |
lilac0112_1 | 0:d35efbf4d62e | 649 | /*軌道の計算、楕円の半分見たいな感じの軌道がベスト*/ |
lilac0112_1 | 0:d35efbf4d62e | 650 | /*半円なのであらかじめステッピングを回転させる必要がある*/ |
lilac0112_1 | 0:d35efbf4d62e | 651 | /*モーター設定*/ |
lilac0112_1 | 0:d35efbf4d62e | 652 | /*ステッピング設定*/ |
lilac0112_1 | 0:d35efbf4d62e | 653 | return; |
lilac0112_1 | 0:d35efbf4d62e | 654 | } |
lilac0112_1 | 0:d35efbf4d62e | 655 | /*軌道の計算、楕円の半分見たいな感じの軌道がベスト*/ |
lilac0112_1 | 0:d35efbf4d62e | 656 | /*半円なのであらかじめステッピングを回転させる必要がある*/ |
lilac0112_1 | 0:d35efbf4d62e | 657 | /*モーター設定*/ |
lilac0112_1 | 0:d35efbf4d62e | 658 | /*ステッピング設定*/ |
lilac0112_1 | 0:d35efbf4d62e | 659 | |
lilac0112_1 | 0:d35efbf4d62e | 660 | |
lilac0112_1 | 0:d35efbf4d62e | 661 | } |
lilac0112_1 | 0:d35efbf4d62e | 662 | void ControlRobo8(int *CompassDef)//BackLeft 7時 |
lilac0112_1 | 0:d35efbf4d62e | 663 | {} |
lilac0112_1 | 0:d35efbf4d62e | 664 | void ControlRobo9(int *CompassDef)//LeftBack 8時 |
lilac0112_1 | 0:d35efbf4d62e | 665 | {} |
lilac0112_1 | 0:d35efbf4d62e | 666 | void ControlRobo10(int *CompassDef)//Left 9時 |
lilac0112_1 | 0:d35efbf4d62e | 667 | {} |
lilac0112_1 | 0:d35efbf4d62e | 668 | void ControlRobo11(int *CompassDef)//LeftFront 10時 |
lilac0112_1 | 0:d35efbf4d62e | 669 | {} |
lilac0112_1 | 0:d35efbf4d62e | 670 | void GoHome(int *CompassDef)//Ball is not found. |
lilac0112_1 | 0:d35efbf4d62e | 671 | { |
lilac0112_1 | 0:d35efbf4d62e | 672 | /*line検知をしないバージョン*/ |
lilac0112_1 | 0:d35efbf4d62e | 673 | int Compass; |
lilac0112_1 | 0:d35efbf4d62e | 674 | char ping[2] = {0}; |
lilac0112_1 | 0:d35efbf4d62e | 675 | |
lilac0112_1 | 0:d35efbf4d62e | 676 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 677 | if(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 678 | while(!((Compass>=150)&&(Compass<=210))){ |
lilac0112_1 | 0:d35efbf4d62e | 679 | move(20,-20);//適当な回転。 |
lilac0112_1 | 0:d35efbf4d62e | 680 | Compass = ((hmc6352.sample() / 10) + 540 - *CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 681 | } |
lilac0112_1 | 0:d35efbf4d62e | 682 | /*return;してもいいかもしれない*/ |
lilac0112_1 | 0:d35efbf4d62e | 683 | } |
lilac0112_1 | 0:d35efbf4d62e | 684 | Step.GoHome(); |
lilac0112_1 | 0:d35efbf4d62e | 685 | Step.BusyWait(0); |
lilac0112_1 | 0:d35efbf4d62e | 686 | |
lilac0112_1 | 0:d35efbf4d62e | 687 | PingReceiveFB(ping); |
lilac0112_1 | 0:d35efbf4d62e | 688 | if(ping[1] >=60){//後ろからの距離60cm |
lilac0112_1 | 0:d35efbf4d62e | 689 | while(ping[1] >=60){ |
lilac0112_1 | 0:d35efbf4d62e | 690 | move(-20,-20); |
lilac0112_1 | 0:d35efbf4d62e | 691 | PingReceiveFB(ping); |
lilac0112_1 | 0:d35efbf4d62e | 692 | } |
lilac0112_1 | 0:d35efbf4d62e | 693 | } |
lilac0112_1 | 0:d35efbf4d62e | 694 | |
lilac0112_1 | 0:d35efbf4d62e | 695 | move(0,0);//stop |
lilac0112_1 | 0:d35efbf4d62e | 696 | |
lilac0112_1 | 0:d35efbf4d62e | 697 | } |
lilac0112_1 | 0:d35efbf4d62e | 698 | /*モーター駆動処理↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑*/ |
lilac0112_1 | 0:d35efbf4d62e | 699 | |
lilac0112_1 | 0:d35efbf4d62e | 700 | uint8_t SwRead(){ |
lilac0112_1 | 0:d35efbf4d62e | 701 | /****** |
lilac0112_1 | 0:d35efbf4d62e | 702 | *返却値はスイッチの状況 |
lilac0112_1 | 0:d35efbf4d62e | 703 | *参照元::aaaaa |
lilac0112_1 | 0:d35efbf4d62e | 704 | * |
lilac0112_1 | 0:d35efbf4d62e | 705 | *Calibration = 0x01; |
lilac0112_1 | 0:d35efbf4d62e | 706 | *Kicker = 0x02; |
lilac0112_1 | 0:d35efbf4d62e | 707 | *Debug1 = 0x04; |
lilac0112_1 | 0:d35efbf4d62e | 708 | *Debug2 = 0x08; |
lilac0112_1 | 0:d35efbf4d62e | 709 | *StartS = 0x10; |
lilac0112_1 | 0:d35efbf4d62e | 710 | * |
lilac0112_1 | 0:d35efbf4d62e | 711 | *****/ |
lilac0112_1 | 0:d35efbf4d62e | 712 | uint8_t i,temp,temp2; |
lilac0112_1 | 0:d35efbf4d62e | 713 | temp = Sw; |
lilac0112_1 | 0:d35efbf4d62e | 714 | if(!(temp == Calibration |
lilac0112_1 | 0:d35efbf4d62e | 715 | ||temp == Kicker |
lilac0112_1 | 0:d35efbf4d62e | 716 | ||temp == Debug1 |
lilac0112_1 | 0:d35efbf4d62e | 717 | ||temp == Debug2 |
lilac0112_1 | 0:d35efbf4d62e | 718 | ||temp == StartS)) return 0;/*スイッチは押されていない状況*/ |
lilac0112_1 | 0:d35efbf4d62e | 719 | if(temp !=0x00){ |
lilac0112_1 | 0:d35efbf4d62e | 720 | for(i = 0; i < 50; i++); |
lilac0112_1 | 0:d35efbf4d62e | 721 | temp2 = Sw; |
lilac0112_1 | 0:d35efbf4d62e | 722 | if(temp == temp2){ |
lilac0112_1 | 0:d35efbf4d62e | 723 | return temp; |
lilac0112_1 | 0:d35efbf4d62e | 724 | } |
lilac0112_1 | 0:d35efbf4d62e | 725 | } |
lilac0112_1 | 0:d35efbf4d62e | 726 | return 0; |
lilac0112_1 | 0:d35efbf4d62e | 727 | } |
lilac0112_1 | 0:d35efbf4d62e | 728 | |
lilac0112_1 | 0:d35efbf4d62e | 729 | //通信(モータ用) |
lilac0112_1 | 0:d35efbf4d62e | 730 | void tx_motor(){ |
lilac0112_1 | 0:d35efbf4d62e | 731 | array(speed[0],speed[1],speed[3],speed[2]); |
lilac0112_1 | 0:d35efbf4d62e | 732 | Motor.printf("%s",StringFIN.c_str()); |
lilac0112_1 | 0:d35efbf4d62e | 733 | } |
lilac0112_1 | 0:d35efbf4d62e | 734 | |
lilac0112_1 | 0:d35efbf4d62e | 735 | void SetUp(int *compass_def){ |
lilac0112_1 | 0:d35efbf4d62e | 736 | /*初期化*/ |
lilac0112_1 | 0:d35efbf4d62e | 737 | Kick = 0; |
lilac0112_1 | 0:d35efbf4d62e | 738 | Sw.mode(PullUp); |
lilac0112_1 | 0:d35efbf4d62e | 739 | Motor.baud(115200); //ボーレート設定 |
lilac0112_1 | 0:d35efbf4d62e | 740 | Motor.printf("1F0002F0003F0004F000\r\n"); //モータ停止 |
lilac0112_1 | 0:d35efbf4d62e | 741 | Motor.attach(&tx_motor,Serial::TxIrq); //送信空き割り込み(モータ用) |
lilac0112_1 | 0:d35efbf4d62e | 742 | move(0,0);//停止 |
lilac0112_1 | 0:d35efbf4d62e | 743 | |
lilac0112_1 | 0:d35efbf4d62e | 744 | //Step.Resets(); |
lilac0112_1 | 0:d35efbf4d62e | 745 | //Step.ReleseSW(0,1); |
lilac0112_1 | 0:d35efbf4d62e | 746 | |
lilac0112_1 | 0:d35efbf4d62e | 747 | Servo.calibrate(0.0005, 120.0); |
lilac0112_1 | 0:d35efbf4d62e | 748 | Servo.position(HOME);//タイヤを前に向ける |
lilac0112_1 | 0:d35efbf4d62e | 749 | |
lilac0112_1 | 0:d35efbf4d62e | 750 | |
lilac0112_1 | 0:d35efbf4d62e | 751 | hmc6352.setOpMode(HMC6352_CONTINUOUS, 1, 20); |
lilac0112_1 | 0:d35efbf4d62e | 752 | *compass_def = (hmc6352.sample() / 10); |
lilac0112_1 | 0:d35efbf4d62e | 753 | |
lilac0112_1 | 0:d35efbf4d62e | 754 | Lcd.cls(); |
lilac0112_1 | 0:d35efbf4d62e | 755 | |
lilac0112_1 | 0:d35efbf4d62e | 756 | /*初期化終了*/ |
lilac0112_1 | 0:d35efbf4d62e | 757 | |
lilac0112_1 | 0:d35efbf4d62e | 758 | |
lilac0112_1 | 0:d35efbf4d62e | 759 | } |
lilac0112_1 | 0:d35efbf4d62e | 760 | void StartLoop(){ |
lilac0112_1 | 0:d35efbf4d62e | 761 | /* |
lilac0112_1 | 0:d35efbf4d62e | 762 | *スイッチが押されるまでロボットはスタートしない. |
lilac0112_1 | 0:d35efbf4d62e | 763 | * |
lilac0112_1 | 0:d35efbf4d62e | 764 | *待っている間にほかのスイッチが押された場合は押されている間その動作をする等. |
lilac0112_1 | 0:d35efbf4d62e | 765 | * |
lilac0112_1 | 0:d35efbf4d62e | 766 | *switch割り当て |
lilac0112_1 | 0:d35efbf4d62e | 767 | *1.コンパスのキャリブレーション実行スイッチ |
lilac0112_1 | 0:d35efbf4d62e | 768 | *2.キッカーのキック(check用) |
lilac0112_1 | 0:d35efbf4d62e | 769 | *3,4.自由 |
lilac0112_1 | 0:d35efbf4d62e | 770 | *5.StartSw |
lilac0112_1 | 0:d35efbf4d62e | 771 | */ |
lilac0112_1 | 0:d35efbf4d62e | 772 | uint8_t State = 0; |
lilac0112_1 | 0:d35efbf4d62e | 773 | |
lilac0112_1 | 0:d35efbf4d62e | 774 | while(1){ |
lilac0112_1 | 0:d35efbf4d62e | 775 | |
lilac0112_1 | 0:d35efbf4d62e | 776 | State = SwRead(); |
lilac0112_1 | 0:d35efbf4d62e | 777 | if(State == 0) continue; |
lilac0112_1 | 0:d35efbf4d62e | 778 | |
lilac0112_1 | 0:d35efbf4d62e | 779 | if(State == Calibration){ |
lilac0112_1 | 0:d35efbf4d62e | 780 | /*calibration command enter... |
lilac0112_1 | 0:d35efbf4d62e | 781 | * |
lilac0112_1 | 0:d35efbf4d62e | 782 | * |
lilac0112_1 | 0:d35efbf4d62e | 783 | */ |
lilac0112_1 | 0:d35efbf4d62e | 784 | continue; |
lilac0112_1 | 0:d35efbf4d62e | 785 | } |
lilac0112_1 | 0:d35efbf4d62e | 786 | if(State == Kicker){ |
lilac0112_1 | 0:d35efbf4d62e | 787 | /* |
lilac0112_1 | 0:d35efbf4d62e | 788 | *kicker check |
lilac0112_1 | 0:d35efbf4d62e | 789 | * |
lilac0112_1 | 0:d35efbf4d62e | 790 | * |
lilac0112_1 | 0:d35efbf4d62e | 791 | */ |
lilac0112_1 | 0:d35efbf4d62e | 792 | continue; |
lilac0112_1 | 0:d35efbf4d62e | 793 | } |
lilac0112_1 | 0:d35efbf4d62e | 794 | if(State == Debug1){ |
lilac0112_1 | 0:d35efbf4d62e | 795 | /* debug command free |
lilac0112_1 | 0:d35efbf4d62e | 796 | * |
lilac0112_1 | 0:d35efbf4d62e | 797 | *display out to selected 3 menus. compass, ir, ping, line,etc... |
lilac0112_1 | 0:d35efbf4d62e | 798 | * |
lilac0112_1 | 0:d35efbf4d62e | 799 | **/ |
lilac0112_1 | 0:d35efbf4d62e | 800 | |
lilac0112_1 | 0:d35efbf4d62e | 801 | } |
lilac0112_1 | 0:d35efbf4d62e | 802 | if(State == Debug2){ |
lilac0112_1 | 0:d35efbf4d62e | 803 | /* debug command free |
lilac0112_1 | 0:d35efbf4d62e | 804 | * |
lilac0112_1 | 0:d35efbf4d62e | 805 | * decide movement of the beginning. |
lilac0112_1 | 0:d35efbf4d62e | 806 | * |
lilac0112_1 | 0:d35efbf4d62e | 807 | * |
lilac0112_1 | 0:d35efbf4d62e | 808 | **/ |
lilac0112_1 | 0:d35efbf4d62e | 809 | |
lilac0112_1 | 0:d35efbf4d62e | 810 | } |
lilac0112_1 | 0:d35efbf4d62e | 811 | if(State == StartS){ |
lilac0112_1 | 0:d35efbf4d62e | 812 | /*game start...*/ |
lilac0112_1 | 0:d35efbf4d62e | 813 | return; |
lilac0112_1 | 0:d35efbf4d62e | 814 | } |
lilac0112_1 | 0:d35efbf4d62e | 815 | |
lilac0112_1 | 0:d35efbf4d62e | 816 | } |
lilac0112_1 | 0:d35efbf4d62e | 817 | |
lilac0112_1 | 0:d35efbf4d62e | 818 | } |
lilac0112_1 | 0:d35efbf4d62e | 819 | int main() { |
lilac0112_1 | 0:d35efbf4d62e | 820 | |
lilac0112_1 | 0:d35efbf4d62e | 821 | /*Ir*/ |
lilac0112_1 | 0:d35efbf4d62e | 822 | uint8_t IrNum;//場所によるirの数を表したもの0~11まではボールがある状態12はボールがない状態 |
lilac0112_1 | 0:d35efbf4d62e | 823 | |
lilac0112_1 | 0:d35efbf4d62e | 824 | /*Line*/ |
lilac0112_1 | 0:d35efbf4d62e | 825 | uint8_t Line; |
lilac0112_1 | 0:d35efbf4d62e | 826 | |
lilac0112_1 | 0:d35efbf4d62e | 827 | /*Compass*/ |
lilac0112_1 | 0:d35efbf4d62e | 828 | int CompassDef = 0, Compass = 0; |
lilac0112_1 | 0:d35efbf4d62e | 829 | |
lilac0112_1 | 0:d35efbf4d62e | 830 | /*State */ |
lilac0112_1 | 0:d35efbf4d62e | 831 | //Direction LineIr = NA;//方位設定奴...エラーでてめんどくさいので後でまたやることにする。 |
lilac0112_1 | 0:d35efbf4d62e | 832 | uint8_t LineIr = NA; |
lilac0112_1 | 0:d35efbf4d62e | 833 | |
lilac0112_1 | 0:d35efbf4d62e | 834 | |
lilac0112_1 | 0:d35efbf4d62e | 835 | |
lilac0112_1 | 0:d35efbf4d62e | 836 | /*関数ポインタ*/ |
lilac0112_1 | 0:d35efbf4d62e | 837 | void (*ControlRobo[13])(int *);//irの位置による分岐 |
lilac0112_1 | 0:d35efbf4d62e | 838 | ControlRobo[0] = ControlRobo0; |
lilac0112_1 | 0:d35efbf4d62e | 839 | ControlRobo[1] = ControlRobo1; |
lilac0112_1 | 0:d35efbf4d62e | 840 | ControlRobo[2] = ControlRobo2; |
lilac0112_1 | 0:d35efbf4d62e | 841 | ControlRobo[3] = ControlRobo3; |
lilac0112_1 | 0:d35efbf4d62e | 842 | ControlRobo[4] = ControlRobo4; |
lilac0112_1 | 0:d35efbf4d62e | 843 | ControlRobo[5] = ControlRobo5; |
lilac0112_1 | 0:d35efbf4d62e | 844 | ControlRobo[6] = ControlRobo6; |
lilac0112_1 | 0:d35efbf4d62e | 845 | ControlRobo[7] = ControlRobo7; |
lilac0112_1 | 0:d35efbf4d62e | 846 | ControlRobo[8] = ControlRobo8; |
lilac0112_1 | 0:d35efbf4d62e | 847 | ControlRobo[9] = ControlRobo9; |
lilac0112_1 | 0:d35efbf4d62e | 848 | ControlRobo[10] = ControlRobo10; |
lilac0112_1 | 0:d35efbf4d62e | 849 | ControlRobo[11] = ControlRobo11; |
lilac0112_1 | 0:d35efbf4d62e | 850 | ControlRobo[12] = GoHome; |
lilac0112_1 | 0:d35efbf4d62e | 851 | |
lilac0112_1 | 0:d35efbf4d62e | 852 | |
lilac0112_1 | 0:d35efbf4d62e | 853 | SetUp(&CompassDef);/*set up routine*/ |
lilac0112_1 | 0:d35efbf4d62e | 854 | |
lilac0112_1 | 0:d35efbf4d62e | 855 | StartLoop(); /*loop stat, switch push end*/ |
lilac0112_1 | 0:d35efbf4d62e | 856 | |
lilac0112_1 | 0:d35efbf4d62e | 857 | /* |
lilac0112_1 | 0:d35efbf4d62e | 858 | 前を向くように設定をするべき |
lilac0112_1 | 0:d35efbf4d62e | 859 | アウトオブバウンズからの復帰時に反対を向けてスタートなので必要。 |
lilac0112_1 | 0:d35efbf4d62e | 860 | */ |
lilac0112_1 | 0:d35efbf4d62e | 861 | while(1){//前を向かせるwhile |
lilac0112_1 | 0:d35efbf4d62e | 862 | Compass = ((hmc6352.sample() / 10) + 540 - CompassDef) % 360; |
lilac0112_1 | 0:d35efbf4d62e | 863 | if(Compass == 3) break;//前を向いたら抜ける。 |
lilac0112_1 | 0:d35efbf4d62e | 864 | } |
lilac0112_1 | 0:d35efbf4d62e | 865 | while(0) { |
lilac0112_1 | 0:d35efbf4d62e | 866 | |
lilac0112_1 | 0:d35efbf4d62e | 867 | Line = LineReceive(); |
lilac0112_1 | 0:d35efbf4d62e | 868 | |
lilac0112_1 | 0:d35efbf4d62e | 869 | if(Line){ //ラインを検知していないか |
lilac0112_1 | 0:d35efbf4d62e | 870 | LineIr = Line & (IrReceiveS()/3 + 1);//計(lineとirの方位を合わせる。 |
lilac0112_1 | 0:d35efbf4d62e | 871 | while(LineIr){ |
lilac0112_1 | 0:d35efbf4d62e | 872 | move(0,0);// |
lilac0112_1 | 0:d35efbf4d62e | 873 | Led[1] = Led[2] = Led[3] = 1; |
lilac0112_1 | 0:d35efbf4d62e | 874 | |
lilac0112_1 | 0:d35efbf4d62e | 875 | LineIr = LineReceive() & (IrReceiveS()/3 + 1); |
lilac0112_1 | 0:d35efbf4d62e | 876 | } |
lilac0112_1 | 0:d35efbf4d62e | 877 | Led[1] = Led[2] = Led[3] = 0; |
lilac0112_1 | 0:d35efbf4d62e | 878 | continue; |
lilac0112_1 | 0:d35efbf4d62e | 879 | |
lilac0112_1 | 0:d35efbf4d62e | 880 | } |
lilac0112_1 | 0:d35efbf4d62e | 881 | |
lilac0112_1 | 0:d35efbf4d62e | 882 | if(Step.BusyCheck()){//ステッピングが動いていないか |
lilac0112_1 | 0:d35efbf4d62e | 883 | continue; |
lilac0112_1 | 0:d35efbf4d62e | 884 | |
lilac0112_1 | 0:d35efbf4d62e | 885 | } |
lilac0112_1 | 0:d35efbf4d62e | 886 | |
lilac0112_1 | 0:d35efbf4d62e | 887 | IrNum = IrReceiveS(); |
lilac0112_1 | 0:d35efbf4d62e | 888 | |
lilac0112_1 | 0:d35efbf4d62e | 889 | (*ControlRobo[IrNum])(&CompassDef);//irの位置によったループ等の処理に移る。 |
lilac0112_1 | 0:d35efbf4d62e | 890 | |
lilac0112_1 | 0:d35efbf4d62e | 891 | //wait_ms(0); |
lilac0112_1 | 0:d35efbf4d62e | 892 | } |
lilac0112_1 | 0:d35efbf4d62e | 893 | |
lilac0112_1 | 0:d35efbf4d62e | 894 | while(1){ |
lilac0112_1 | 0:d35efbf4d62e | 895 | /*デモプログラム |
lilac0112_1 | 0:d35efbf4d62e | 896 | * |
lilac0112_1 | 0:d35efbf4d62e | 897 | *ぐるぐる |
lilac0112_1 | 0:d35efbf4d62e | 898 | * |
lilac0112_1 | 0:d35efbf4d62e | 899 | *Servoの場合、ボールを中心にしなければ円軌道を作るのは困難 |
lilac0112_1 | 0:d35efbf4d62e | 900 | */ |
lilac0112_1 | 0:d35efbf4d62e | 901 | move(30,30); |
lilac0112_1 | 0:d35efbf4d62e | 902 | |
lilac0112_1 | 0:d35efbf4d62e | 903 | wait(1); |
lilac0112_1 | 0:d35efbf4d62e | 904 | |
lilac0112_1 | 0:d35efbf4d62e | 905 | move(-30,-30); |
lilac0112_1 | 0:d35efbf4d62e | 906 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 907 | |
lilac0112_1 | 0:d35efbf4d62e | 908 | Step.Run(1,1200); |
lilac0112_1 | 0:d35efbf4d62e | 909 | move(10,10); |
lilac0112_1 | 0:d35efbf4d62e | 910 | wait(1.5); |
lilac0112_1 | 0:d35efbf4d62e | 911 | |
lilac0112_1 | 0:d35efbf4d62e | 912 | move(0,0); |
lilac0112_1 | 0:d35efbf4d62e | 913 | Step.SoftStop(); |
lilac0112_1 | 0:d35efbf4d62e | 914 | |
lilac0112_1 | 0:d35efbf4d62e | 915 | wait(0.5); |
lilac0112_1 | 0:d35efbf4d62e | 916 | |
lilac0112_1 | 0:d35efbf4d62e | 917 | Step.GoHome(); |
lilac0112_1 | 0:d35efbf4d62e | 918 | |
lilac0112_1 | 0:d35efbf4d62e | 919 | wait(1.5); |
lilac0112_1 | 0:d35efbf4d62e | 920 | |
lilac0112_1 | 0:d35efbf4d62e | 921 | |
lilac0112_1 | 0:d35efbf4d62e | 922 | |
lilac0112_1 | 0:d35efbf4d62e | 923 | } |
lilac0112_1 | 0:d35efbf4d62e | 924 | |
lilac0112_1 | 0:d35efbf4d62e | 925 | } |