MEC-B / Mbed 2 deprecated AR_MastarNode_copy

Dependencies:   DriveConroller IMU MDD Mycan Odometer PID RotaryEncoder UART USS mbed

Fork of AR_MastarNode by MEC-B

Committer:
soyooo
Date:
Sun Aug 26 09:07:19 2018 +0000
Revision:
9:ce5a1315fe0d
Parent:
8:123cd1f07aea
Child:
10:ebb59c1d369e
???????

Who changed what in which revision?

UserRevisionLine numberNew contents of line
TanakaTarou 0:6db16ad02a1b 1 #include "mbed.h"
TanakaTarou 0:6db16ad02a1b 2 #include "DriveController.h"
TanakaTarou 0:6db16ad02a1b 3 #include "IMU.h"
TanakaTarou 0:6db16ad02a1b 4 #include "MDD.h"
TanakaTarou 0:6db16ad02a1b 5 #include "MDD2.h"
TanakaTarou 0:6db16ad02a1b 6 #include "Mycan.h"
TanakaTarou 0:6db16ad02a1b 7 #include "Odometer.h"
TanakaTarou 0:6db16ad02a1b 8 #include "PID.h"
TanakaTarou 0:6db16ad02a1b 9 #include "RotaryEncoder.h"
TanakaTarou 0:6db16ad02a1b 10 #include "SBUS.h"
TanakaTarou 0:6db16ad02a1b 11 #include "USS.h"
TanakaTarou 0:6db16ad02a1b 12 #include "hardwareConfig.h"
soyooo 9:ce5a1315fe0d 13 #include "stateLib.h"
TanakaTarou 0:6db16ad02a1b 14
soyooo 9:ce5a1315fe0d 15 elements getRobotVelocity(state);
soyooo 9:ce5a1315fe0d 16 state getTargetState();
soyooo 9:ce5a1315fe0d 17 int updateStateNum();
soyooo 9:ce5a1315fe0d 18 bool isConvergetnceTops(int);
TanakaTarou 0:6db16ad02a1b 19
soyooo 9:ce5a1315fe0d 20 controller getPropoData();
TanakaTarou 0:6db16ad02a1b 21
TanakaTarou 0:6db16ad02a1b 22 //x軸補正用 PID
soyooo 1:d7ceb38da3d8 23 PID pidRobotX(2, 0, 0, 0.01, 0.3, &timer);
TanakaTarou 0:6db16ad02a1b 24 float target_x = 0;
TanakaTarou 0:6db16ad02a1b 25
TanakaTarou 0:6db16ad02a1b 26 //y軸補正用 PID
soyooo 1:d7ceb38da3d8 27 PID pidRobotY(2, 0, 0, 0.01, 0.3, &timer);
TanakaTarou 0:6db16ad02a1b 28 float target_y = 0;
TanakaTarou 0:6db16ad02a1b 29
soyooo 1:d7ceb38da3d8 30 //yow角補正用 (Pgain, Igain, Dgain, 制御ループ時間[s], 計算出力100%定義)
soyooo 9:ce5a1315fe0d 31 PID pidRobotYow(0.05, 0, 0, 0.01, 0.8, &timer);
soyooo 1:d7ceb38da3d8 32 float target_yow = 0;
soyooo 9:ce5a1315fe0d 33
TanakaTarou 0:6db16ad02a1b 34 //USS用
TanakaTarou 5:7c5e07260e1e 35 PID pidUss(0.025, 0, 0, 0.1, 0.3, &timer);
soyooo 9:ce5a1315fe0d 36 float target_uss = 0;
TanakaTarou 3:6b4adb4d7101 37
TanakaTarou 0:6db16ad02a1b 38 int main()
TanakaTarou 0:6db16ad02a1b 39 {
TanakaTarou 0:6db16ad02a1b 40 //タイマー3の優先度を最低にする
soyooo 9:ce5a1315fe0d 41 NVIC_SetPriority(TIMER3_IRQn, 3);
TanakaTarou 0:6db16ad02a1b 42
TanakaTarou 0:6db16ad02a1b 43 //IMUのキャリブレーション
TanakaTarou 4:9f74525eb37f 44 wait(1);
TanakaTarou 0:6db16ad02a1b 45 imu.performCalibration();
TanakaTarou 0:6db16ad02a1b 46 imu.startAngleComputing();
TanakaTarou 5:7c5e07260e1e 47
TanakaTarou 5:7c5e07260e1e 48 uss.startTriger();
soyooo 9:ce5a1315fe0d 49
soyooo 9:ce5a1315fe0d 50 enc[0].changeDirection();
soyooo 9:ce5a1315fe0d 51 enc[1].changeDirection();
soyooo 9:ce5a1315fe0d 52 enc[2].changeDirection();
TanakaTarou 0:6db16ad02a1b 53
TanakaTarou 0:6db16ad02a1b 54 //オドメーターの定義
TanakaTarou 0:6db16ad02a1b 55 float matrix[3][3] = {{1, 0, 0},
TanakaTarou 0:6db16ad02a1b 56 {0, 1, 0},
TanakaTarou 0:6db16ad02a1b 57 {0, 0, 0}
TanakaTarou 0:6db16ad02a1b 58 };
soyooo 9:ce5a1315fe0d 59 Odometer odm(matrix, 0.050);
TanakaTarou 0:6db16ad02a1b 60 float tmp = 0;
TanakaTarou 0:6db16ad02a1b 61 float *encoders[3] = {&enc[0].rotations, &enc[1].rotations, &tmp};
TanakaTarou 0:6db16ad02a1b 62 odm.setupOdometerSensors(encoders, &imu.angle[2]);
soyooo 9:ce5a1315fe0d 63 odm.startComputingOdometry(0.01, 0, 0, 0);
soyooo 9:ce5a1315fe0d 64 mecanum.imu_yow = &imu.angle[2];
soyooo 9:ce5a1315fe0d 65
soyooo 9:ce5a1315fe0d 66 //許容誤差
soyooo 9:ce5a1315fe0d 67 pidRobotX.allowable_error = 0.1;
soyooo 9:ce5a1315fe0d 68 pidRobotY.allowable_error = 0.1;
soyooo 9:ce5a1315fe0d 69 pidRobotYow.allowable_error = 2;
soyooo 9:ce5a1315fe0d 70 pidUss.allowable_error = 3;
soyooo 9:ce5a1315fe0d 71
TanakaTarou 7:1ee46b2e8dce 72 //PID設定
TanakaTarou 0:6db16ad02a1b 73 pidRobotX.sensor = &odm.x;
TanakaTarou 0:6db16ad02a1b 74 pidRobotX.target = &target_x;
TanakaTarou 0:6db16ad02a1b 75 pidRobotX.start();
TanakaTarou 0:6db16ad02a1b 76 pidRobotY.sensor = &odm.y;
TanakaTarou 0:6db16ad02a1b 77 pidRobotY.target = &target_y;
TanakaTarou 0:6db16ad02a1b 78 pidRobotY.start();
TanakaTarou 5:7c5e07260e1e 79 pidRobotYow.sensor = &imu.angle[2];
TanakaTarou 5:7c5e07260e1e 80 pidRobotYow.target = &target_yow;
TanakaTarou 5:7c5e07260e1e 81 pidRobotYow.start();
TanakaTarou 5:7c5e07260e1e 82 pidUss.sensor = &uss.distance;
TanakaTarou 5:7c5e07260e1e 83 pidUss.target = &target_uss;
TanakaTarou 5:7c5e07260e1e 84 pidUss.start();
TanakaTarou 5:7c5e07260e1e 85
TanakaTarou 4:9f74525eb37f 86 //マイクロスイッチ
TanakaTarou 3:6b4adb4d7101 87 sw1.mode(PullUp);
TanakaTarou 3:6b4adb4d7101 88 sw2.mode(PullUp);
TanakaTarou 3:6b4adb4d7101 89
soyooo 9:ce5a1315fe0d 90 odm.x = 0;
soyooo 9:ce5a1315fe0d 91 timer.start();
soyooo 9:ce5a1315fe0d 92
TanakaTarou 6:a102603c99fd 93 while(1)
TanakaTarou 0:6db16ad02a1b 94 {
soyooo 9:ce5a1315fe0d 95 //controller cmd = getPropoData(); //getPropoData & getCanData
soyooo 9:ce5a1315fe0d 96 //float robot_velocity[3] = {cmd.LX, cmd.LY, cmd.RX};
soyooo 9:ce5a1315fe0d 97
TanakaTarou 7:1ee46b2e8dce 98 can.read();
soyooo 9:ce5a1315fe0d 99
soyooo 9:ce5a1315fe0d 100 //目指すべきロボットの状態を取得
soyooo 9:ce5a1315fe0d 101 state tar_state = getTargetState();
TanakaTarou 0:6db16ad02a1b 102
soyooo 9:ce5a1315fe0d 103 //canに置く
soyooo 9:ce5a1315fe0d 104 can.set(1, 1, tar_state.shoot);
soyooo 9:ce5a1315fe0d 105 //角度は2倍して送って、2で割って受け取る 角度可変が0.5度刻みにできる
soyooo 9:ce5a1315fe0d 106 can.set(1, 2, int (tar_state.angle * 2));
soyooo 9:ce5a1315fe0d 107 can.set(1, 3, tar_state.supply);
TanakaTarou 3:6b4adb4d7101 108
soyooo 9:ce5a1315fe0d 109 //送信周期調整
soyooo 9:ce5a1315fe0d 110 static double pre_time = 0;
soyooo 9:ce5a1315fe0d 111 double now_time = timer.read();
soyooo 9:ce5a1315fe0d 112 if(now_time - pre_time >= 0.01)
soyooo 1:d7ceb38da3d8 113 {
soyooo 9:ce5a1315fe0d 114 while(can.send() == 0);
soyooo 9:ce5a1315fe0d 115 pre_time = now_time;
TanakaTarou 8:123cd1f07aea 116 }
TanakaTarou 8:123cd1f07aea 117
soyooo 9:ce5a1315fe0d 118 if(sw2 == 1)
TanakaTarou 0:6db16ad02a1b 119 {
soyooo 9:ce5a1315fe0d 120 odm.x = 0;
soyooo 9:ce5a1315fe0d 121 odm.y = 0;
soyooo 9:ce5a1315fe0d 122 imu.angle[2] = 0;
TanakaTarou 0:6db16ad02a1b 123 }
soyooo 9:ce5a1315fe0d 124
soyooo 9:ce5a1315fe0d 125 //ロボット速度を取得
soyooo 9:ce5a1315fe0d 126 elements robot_vel = getRobotVelocity(tar_state);
soyooo 9:ce5a1315fe0d 127 float robot_velocity[3] = {robot_vel.x, robot_vel.y, robot_vel.theta};
soyooo 9:ce5a1315fe0d 128
TanakaTarou 0:6db16ad02a1b 129 //ホイール速度計算
TanakaTarou 4:9f74525eb37f 130 mecanum.setVelG(robot_velocity);
TanakaTarou 0:6db16ad02a1b 131 mecanum.computeWheelVel();
TanakaTarou 0:6db16ad02a1b 132 mecanum.rescaleWheelVel();
TanakaTarou 0:6db16ad02a1b 133
TanakaTarou 0:6db16ad02a1b 134 //モーターの駆動
TanakaTarou 0:6db16ad02a1b 135 for(int i = 0; i < 4; i++)
TanakaTarou 3:6b4adb4d7101 136 Motor[i].drive(mecanum.wheel_vel[i]);
TanakaTarou 0:6db16ad02a1b 137
soyooo 9:ce5a1315fe0d 138 //pc.printf("%.2f\t", enc[0].rotations);
soyooo 9:ce5a1315fe0d 139
TanakaTarou 3:6b4adb4d7101 140 pc.printf("%.2f\t", odm.x);
TanakaTarou 3:6b4adb4d7101 141 pc.printf("%.2f\t", odm.y);
TanakaTarou 3:6b4adb4d7101 142 pc.printf("%.2f\t", imu.angle[2]);
TanakaTarou 3:6b4adb4d7101 143 pc.printf("%.2f\t", uss.distance);
soyooo 9:ce5a1315fe0d 144 pc.printf("%.2f\t", target_yow);
soyooo 9:ce5a1315fe0d 145 pc.printf("%.2f\t", pidRobotYow.target);
soyooo 9:ce5a1315fe0d 146 pc.printf("%d\t", can.get(4, 1));
soyooo 9:ce5a1315fe0d 147
TanakaTarou 2:7af15d4ee55a 148
soyooo 9:ce5a1315fe0d 149 //pc.printf("%.2f\t", enc[0].rotations);
soyooo 9:ce5a1315fe0d 150 /*
soyooo 9:ce5a1315fe0d 151 pc.printf("%.2f\t", tar_state.y);
soyooo 9:ce5a1315fe0d 152 pc.printf("%.2f\t", tar_state.theta);
soyooo 9:ce5a1315fe0d 153 pc.printf("%.2f\t", tar_state.shoot);
soyooo 9:ce5a1315fe0d 154 pc.printf("%.2f\t", tar_state.angle);
soyooo 9:ce5a1315fe0d 155 pc.printf("%.2f\t", tar_state.supply);
soyooo 9:ce5a1315fe0d 156 */
soyooo 9:ce5a1315fe0d 157 pc.printf("\n");
TanakaTarou 0:6db16ad02a1b 158 }
TanakaTarou 0:6db16ad02a1b 159 }
TanakaTarou 0:6db16ad02a1b 160
soyooo 9:ce5a1315fe0d 161 state getTargetState()
soyooo 9:ce5a1315fe0d 162 {
soyooo 9:ce5a1315fe0d 163 static bool start_flag = 0;
soyooo 9:ce5a1315fe0d 164
soyooo 9:ce5a1315fe0d 165 int num;
soyooo 9:ce5a1315fe0d 166
soyooo 9:ce5a1315fe0d 167 /*
soyooo 9:ce5a1315fe0d 168 スタートボタン待機
soyooo 9:ce5a1315fe0d 169 whileにするとほかの処理がすべて止めるためこれを回避
soyooo 9:ce5a1315fe0d 170 */
soyooo 9:ce5a1315fe0d 171 if(sw1 == 1)
soyooo 9:ce5a1315fe0d 172 start_flag = 1;
soyooo 9:ce5a1315fe0d 173
soyooo 9:ce5a1315fe0d 174 //sw1が1度も押されていないとき、num = 0 を強制
soyooo 9:ce5a1315fe0d 175 if(!start_flag)
soyooo 9:ce5a1315fe0d 176 num = 0;
soyooo 9:ce5a1315fe0d 177 else num = updateStateNum();
soyooo 9:ce5a1315fe0d 178
soyooo 9:ce5a1315fe0d 179 //num = 0 なので、再びスタート待機
soyooo 9:ce5a1315fe0d 180 if(num == 0)
soyooo 9:ce5a1315fe0d 181 start_flag = 0;
soyooo 9:ce5a1315fe0d 182
soyooo 9:ce5a1315fe0d 183 state a;
soyooo 9:ce5a1315fe0d 184 //states辞典から値を引っ張る
soyooo 9:ce5a1315fe0d 185 a.x = state_lib[num][0];
soyooo 9:ce5a1315fe0d 186 a.y = state_lib[num][1];
soyooo 9:ce5a1315fe0d 187 a.theta = state_lib[num][2];
soyooo 9:ce5a1315fe0d 188 a.shoot = state_lib[num][3];
soyooo 9:ce5a1315fe0d 189 a.angle = state_lib[num][4];
soyooo 9:ce5a1315fe0d 190 a.supply = state_lib[num][5];
soyooo 9:ce5a1315fe0d 191 return a;
soyooo 9:ce5a1315fe0d 192 }
soyooo 9:ce5a1315fe0d 193
soyooo 9:ce5a1315fe0d 194 int updateStateNum()
soyooo 9:ce5a1315fe0d 195 {
soyooo 9:ce5a1315fe0d 196 /*
soyooo 9:ce5a1315fe0d 197 状態収束を判定して次のステップに進む
soyooo 9:ce5a1315fe0d 198 */
soyooo 9:ce5a1315fe0d 199 float t = 0.1;
soyooo 9:ce5a1315fe0d 200 static int num = 0;
soyooo 9:ce5a1315fe0d 201 //x方向、y方向、yow方向の判定をはっきりしておく
soyooo 9:ce5a1315fe0d 202 bool flag_x = 0, flag_y = 0, flag_yow = 0;
soyooo 9:ce5a1315fe0d 203
soyooo 9:ce5a1315fe0d 204 if(pidRobotYow.isConvergence(t))
soyooo 9:ce5a1315fe0d 205 flag_yow = 1;
soyooo 9:ce5a1315fe0d 206
soyooo 9:ce5a1315fe0d 207 //超音波で近づくとき
soyooo 9:ce5a1315fe0d 208 if(state_lib[num][1] >= 10)
soyooo 9:ce5a1315fe0d 209 {
soyooo 9:ce5a1315fe0d 210 if(pidUss.isConvergence(t+1) == 1 && isConvergetnceTops(num) == 1)
soyooo 9:ce5a1315fe0d 211 flag_y = 1;
soyooo 9:ce5a1315fe0d 212 }
soyooo 9:ce5a1315fe0d 213 else if(pidRobotY.isConvergence(t) == 1)
soyooo 9:ce5a1315fe0d 214 flag_y = 1;
soyooo 9:ce5a1315fe0d 215
soyooo 9:ce5a1315fe0d 216 if(state_lib[num][0] >= 10)
soyooo 9:ce5a1315fe0d 217 {
soyooo 9:ce5a1315fe0d 218 if(pidUss.isConvergence(t+1) == 1 && isConvergetnceTops(num) == 1)
soyooo 9:ce5a1315fe0d 219 flag_x = 1;
soyooo 9:ce5a1315fe0d 220 }
soyooo 9:ce5a1315fe0d 221 else if(pidRobotX.isConvergence(t) == 1)
soyooo 9:ce5a1315fe0d 222 flag_x = 1;
soyooo 9:ce5a1315fe0d 223
soyooo 9:ce5a1315fe0d 224 //全部が収束してるか
soyooo 9:ce5a1315fe0d 225 if(flag_x && flag_y && flag_yow)
soyooo 9:ce5a1315fe0d 226 num++;
soyooo 9:ce5a1315fe0d 227
soyooo 9:ce5a1315fe0d 228 //振り出しに戻る
soyooo 9:ce5a1315fe0d 229 if(num >= LIBNUM)
soyooo 9:ce5a1315fe0d 230 {
soyooo 9:ce5a1315fe0d 231 num = 0;
soyooo 9:ce5a1315fe0d 232 }
soyooo 9:ce5a1315fe0d 233
soyooo 9:ce5a1315fe0d 234 return num;
soyooo 9:ce5a1315fe0d 235 }
soyooo 9:ce5a1315fe0d 236
soyooo 9:ce5a1315fe0d 237 elements getRobotVelocity(state a)
soyooo 9:ce5a1315fe0d 238 {
soyooo 9:ce5a1315fe0d 239 elements vel;
soyooo 9:ce5a1315fe0d 240
soyooo 9:ce5a1315fe0d 241 //yow角調整処理
soyooo 9:ce5a1315fe0d 242 *pidRobotYow.target = a.theta;
soyooo 9:ce5a1315fe0d 243 vel.theta = pidRobotYow.output;
soyooo 9:ce5a1315fe0d 244
soyooo 9:ce5a1315fe0d 245
soyooo 9:ce5a1315fe0d 246 //USS距離調整処理
soyooo 9:ce5a1315fe0d 247 if(a.x >= 10)
soyooo 9:ce5a1315fe0d 248 {
soyooo 9:ce5a1315fe0d 249 *pidUss.target = a.x - 10;
soyooo 9:ce5a1315fe0d 250 vel.x = -pidUss.output;
soyooo 9:ce5a1315fe0d 251 }
soyooo 9:ce5a1315fe0d 252 else
soyooo 9:ce5a1315fe0d 253 {
soyooo 9:ce5a1315fe0d 254 *pidRobotX.target = a.x;
soyooo 9:ce5a1315fe0d 255 vel.x = pidRobotX.output;
soyooo 9:ce5a1315fe0d 256 }
soyooo 9:ce5a1315fe0d 257
soyooo 9:ce5a1315fe0d 258 //USS距離調整処理
soyooo 9:ce5a1315fe0d 259 if(a.y >= 10)
soyooo 9:ce5a1315fe0d 260 {
soyooo 9:ce5a1315fe0d 261 *pidUss.target = a.y - 10;
soyooo 9:ce5a1315fe0d 262 vel.y = -pidUss.output;
soyooo 9:ce5a1315fe0d 263 }
soyooo 9:ce5a1315fe0d 264 else
soyooo 9:ce5a1315fe0d 265 {
soyooo 9:ce5a1315fe0d 266 //y軸調整処理
soyooo 9:ce5a1315fe0d 267 *pidRobotY.target = a.y;
soyooo 9:ce5a1315fe0d 268 vel.y = pidRobotY.output;
soyooo 9:ce5a1315fe0d 269 }
soyooo 9:ce5a1315fe0d 270
soyooo 9:ce5a1315fe0d 271 return vel;
soyooo 9:ce5a1315fe0d 272 }
soyooo 9:ce5a1315fe0d 273 bool isConvergetnceTops(int state_num)
TanakaTarou 0:6db16ad02a1b 274 {
TanakaTarou 4:9f74525eb37f 275 int velocity_pid = can.get(3, 1);
TanakaTarou 4:9f74525eb37f 276 int angle_pid = can.get(3, 2);
TanakaTarou 4:9f74525eb37f 277 int velocity_val = can.get(3, 3);
soyooo 9:ce5a1315fe0d 278 float angle_val = can.get(3, 4);
TanakaTarou 3:6b4adb4d7101 279
soyooo 9:ce5a1315fe0d 280 angle_val /= 2.0;
soyooo 9:ce5a1315fe0d 281 if(angle_pid == 1 && velocity_pid == 1 && velocity_val == state_lib[state_num][3] && angle_val == state_lib[state_num][4])
TanakaTarou 4:9f74525eb37f 282 return 1;
TanakaTarou 3:6b4adb4d7101 283 else return 0;
soyooo 9:ce5a1315fe0d 284 }
soyooo 9:ce5a1315fe0d 285
soyooo 9:ce5a1315fe0d 286 controller getPropoData()
soyooo 9:ce5a1315fe0d 287 {
soyooo 9:ce5a1315fe0d 288 float dead_zone = 0.05;
soyooo 9:ce5a1315fe0d 289 controller propo;
soyooo 9:ce5a1315fe0d 290 sbus.isFailSafe();
soyooo 9:ce5a1315fe0d 291
soyooo 9:ce5a1315fe0d 292 //propo直接コントロール
soyooo 9:ce5a1315fe0d 293 if(sbus.isFailSafe())
soyooo 9:ce5a1315fe0d 294 {
soyooo 9:ce5a1315fe0d 295 propo.LX = propo.LY = propo.RX = propo.RY = 0;
soyooo 9:ce5a1315fe0d 296 propo.H = propo.A = propo.D = propo.F = propo.G = 0;
soyooo 9:ce5a1315fe0d 297 }
soyooo 9:ce5a1315fe0d 298 else
soyooo 9:ce5a1315fe0d 299 {
soyooo 9:ce5a1315fe0d 300 propo.LX = sbus.getStickVal(0) / 255.0;
soyooo 9:ce5a1315fe0d 301 propo.LY = sbus.getStickVal(1) / 255.0;
soyooo 9:ce5a1315fe0d 302 propo.RX = -sbus.getStickVal(2) / 255.0;
soyooo 9:ce5a1315fe0d 303 propo.RY = sbus.getStickVal(3) / 255.0;
soyooo 9:ce5a1315fe0d 304 propo.H = sbus.getSwitchVal(0);
soyooo 9:ce5a1315fe0d 305 propo.A = sbus.getSwitchVal(1);
soyooo 9:ce5a1315fe0d 306 propo.D = sbus.getSwitchVal(2);
soyooo 9:ce5a1315fe0d 307 propo.F = sbus.getSwitchVal(3);
soyooo 9:ce5a1315fe0d 308 propo.G = sbus.getSwitchVal(4);
soyooo 9:ce5a1315fe0d 309 }
soyooo 9:ce5a1315fe0d 310
soyooo 9:ce5a1315fe0d 311 if(propo.RX < dead_zone && propo.RX > -dead_zone) propo.RX = 0;
soyooo 9:ce5a1315fe0d 312 if(propo.RY < dead_zone && propo.RY > -dead_zone) propo.RY = 0;
soyooo 9:ce5a1315fe0d 313 if(propo.LX < dead_zone && propo.LX > -dead_zone) propo.LX = 0;
soyooo 9:ce5a1315fe0d 314 if(propo.LY < dead_zone && propo.LY > -dead_zone) propo.LY = 0;
soyooo 9:ce5a1315fe0d 315 return propo;
soyooo 9:ce5a1315fe0d 316 }