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:
TanakaTarou
Date:
Mon Aug 06 10:12:44 2018 +0000
Revision:
2:7af15d4ee55a
Parent:
1:d7ceb38da3d8
Child:
3:6b4adb4d7101
8/6

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 "CSV.h"
TanakaTarou 0:6db16ad02a1b 11 #include "SBUS.h"
TanakaTarou 0:6db16ad02a1b 12 #include "USS.h"
TanakaTarou 0:6db16ad02a1b 13 #include "hardwareConfig.h"
TanakaTarou 0:6db16ad02a1b 14
TanakaTarou 0:6db16ad02a1b 15 //(X, Y, θ, speed, angle, injection, 補給昇降)
TanakaTarou 2:7af15d4ee55a 16 float position[13][7] = {{0.0, 0.0, 0.0, 0, 90, 0, 0.0},//初期位置
TanakaTarou 2:7af15d4ee55a 17 {-0.3, 0.0, 0.0, 0, 86, 0, 0.0},//x移動, 角度変化
TanakaTarou 2:7af15d4ee55a 18 {-0.3, 20.0, 0.0, 0, 86, 0, 0.0},//y移動
TanakaTarou 2:7af15d4ee55a 19 {-0.3, 20.0, 0.0, 10, 86, 1, 0.0},//発射
TanakaTarou 2:7af15d4ee55a 20 {-0.3, 0.0, 0.0, 0, 82, 0, 0.0},//y移動,角度戻す, P上昇
TanakaTarou 0:6db16ad02a1b 21
TanakaTarou 2:7af15d4ee55a 22 {-0.6, 0.0, 0.0, 0, 82, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動
TanakaTarou 2:7af15d4ee55a 23 {-0.6, 20.0, 0.0, 0, 82, 0, 0.0},//y移動
TanakaTarou 2:7af15d4ee55a 24 {-0.6, 20.0, 0.0, 10, 80, 1, 0.0},//発射
TanakaTarou 2:7af15d4ee55a 25 {-0.6, 0.0, 0.0, 0, 78, 0, 6.8},//y移動,角度戻す, P上昇
TanakaTarou 0:6db16ad02a1b 26
TanakaTarou 2:7af15d4ee55a 27 {-0.9, 0.0, 0.0, 0, 78, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動
TanakaTarou 2:7af15d4ee55a 28 {-0.9, 20.0, 0.0, 0, 78, 0, 0.0},//y移動
TanakaTarou 2:7af15d4ee55a 29 {-0.9, 20.0, 0.0, 10, 78, 1, 0.0},//発射
TanakaTarou 2:7af15d4ee55a 30 {-0.9, 0.0, 0.0, 0, 90, 0, 6.8},//y移動,角度戻す, P上昇
TanakaTarou 0:6db16ad02a1b 31 /*
TanakaTarou 0:6db16ad02a1b 32 {3.0, 0.0, 0.0, 20, 80, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動
TanakaTarou 0:6db16ad02a1b 33 {3.0, 2.5, 0.0, 20, 80, 0, 0.0},//y移動
TanakaTarou 0:6db16ad02a1b 34 {3.0, 2.5, 0.0, 20, 80, 1, 0.0},//下段に発射
TanakaTarou 0:6db16ad02a1b 35 {3.0, 2.5, 0.0, 20, 90, 0, 6.8},//角度戻す, P上昇
TanakaTarou 0:6db16ad02a1b 36 {3.0, 2.5, 0.0, 20, 80, 0, 0.0},//角度変化, 下降&バットマン駆動
TanakaTarou 0:6db16ad02a1b 37 {3.0, 2.5, 0.0, 20, 80, 1, 0.0},//上段に発射
TanakaTarou 0:6db16ad02a1b 38 */
TanakaTarou 0:6db16ad02a1b 39 };
TanakaTarou 0:6db16ad02a1b 40
TanakaTarou 0:6db16ad02a1b 41 controller getPropoData();
TanakaTarou 0:6db16ad02a1b 42 //bool isConvergence(int num);
TanakaTarou 0:6db16ad02a1b 43
TanakaTarou 0:6db16ad02a1b 44 //x軸補正用 PID
soyooo 1:d7ceb38da3d8 45 PID pidRobotX(2, 0, 0, 0.01, 0.3, &timer);
TanakaTarou 0:6db16ad02a1b 46 float target_x = 0;
TanakaTarou 0:6db16ad02a1b 47
TanakaTarou 0:6db16ad02a1b 48 //y軸補正用 PID
soyooo 1:d7ceb38da3d8 49 PID pidRobotY(2, 0, 0, 0.01, 0.3, &timer);
TanakaTarou 0:6db16ad02a1b 50 float target_y = 0;
TanakaTarou 0:6db16ad02a1b 51
soyooo 1:d7ceb38da3d8 52 //yow角補正用 (Pgain, Igain, Dgain, 制御ループ時間[s], 計算出力100%定義)
soyooo 1:d7ceb38da3d8 53 PID pidRobotYow(0.05, 0, 0, 0.01, 0.95, &timer);
soyooo 1:d7ceb38da3d8 54 float target_yow = 0;
soyooo 1:d7ceb38da3d8 55
TanakaTarou 0:6db16ad02a1b 56 //USS用
soyooo 1:d7ceb38da3d8 57 PID pidUss(0.02, 0, 0, 0.01, 0.3, &timer);
TanakaTarou 0:6db16ad02a1b 58 float target_uss = 25.0;
TanakaTarou 0:6db16ad02a1b 59
TanakaTarou 0:6db16ad02a1b 60 int main()
TanakaTarou 0:6db16ad02a1b 61 {
TanakaTarou 0:6db16ad02a1b 62 //タイマー3の優先度を最低にする
TanakaTarou 0:6db16ad02a1b 63 NVIC_SetPriority(TIMER3_IRQn, 100);
TanakaTarou 0:6db16ad02a1b 64
TanakaTarou 0:6db16ad02a1b 65 //IMUのキャリブレーション
TanakaTarou 0:6db16ad02a1b 66 imu.performCalibration();
TanakaTarou 0:6db16ad02a1b 67 imu.startAngleComputing();
TanakaTarou 0:6db16ad02a1b 68
TanakaTarou 0:6db16ad02a1b 69 for(int i; i < 3; i++)
TanakaTarou 0:6db16ad02a1b 70 enc[i].changeDirection();
TanakaTarou 0:6db16ad02a1b 71
TanakaTarou 0:6db16ad02a1b 72 //オドメーターの定義
TanakaTarou 0:6db16ad02a1b 73 float matrix[3][3] = {{1, 0, 0},
TanakaTarou 0:6db16ad02a1b 74 {0, 1, 0},
TanakaTarou 0:6db16ad02a1b 75 {0, 0, 0}
TanakaTarou 0:6db16ad02a1b 76 };
TanakaTarou 0:6db16ad02a1b 77 Odometer odm(matrix, 0.048);
TanakaTarou 0:6db16ad02a1b 78 float tmp = 0;
TanakaTarou 0:6db16ad02a1b 79 float *encoders[3] = {&enc[0].rotations, &enc[1].rotations, &tmp};
TanakaTarou 0:6db16ad02a1b 80 odm.setupOdometerSensors(encoders, &imu.angle[2]);
TanakaTarou 0:6db16ad02a1b 81 odm.startComputingOdometry(0.005, 0, 0, 0);
TanakaTarou 0:6db16ad02a1b 82
TanakaTarou 0:6db16ad02a1b 83 //オドメーターX
TanakaTarou 0:6db16ad02a1b 84 pidRobotX.sensor = &odm.x;
TanakaTarou 0:6db16ad02a1b 85 pidRobotX.target = &target_x;
TanakaTarou 0:6db16ad02a1b 86 pidRobotX.start();
TanakaTarou 0:6db16ad02a1b 87
TanakaTarou 0:6db16ad02a1b 88 //オドメーターY
TanakaTarou 0:6db16ad02a1b 89 pidRobotY.sensor = &odm.y;
TanakaTarou 0:6db16ad02a1b 90 pidRobotY.target = &target_y;
TanakaTarou 0:6db16ad02a1b 91 pidRobotY.start();
soyooo 1:d7ceb38da3d8 92
soyooo 1:d7ceb38da3d8 93 //IMUyow
soyooo 1:d7ceb38da3d8 94 mecanum.imu_yow = &imu.angle[2];
soyooo 1:d7ceb38da3d8 95 pidRobotYow.sensor = &imu.angle[2];
soyooo 1:d7ceb38da3d8 96 pidRobotYow.target = &target_yow;
soyooo 1:d7ceb38da3d8 97 pidRobotYow.start();
soyooo 1:d7ceb38da3d8 98
TanakaTarou 0:6db16ad02a1b 99 //USS pid設定
TanakaTarou 0:6db16ad02a1b 100 uss.startTriger();
TanakaTarou 0:6db16ad02a1b 101 pidUss.sensor = &uss.distance;
TanakaTarou 0:6db16ad02a1b 102 pidUss.target = &target_uss;
TanakaTarou 0:6db16ad02a1b 103 pidUss.start();
soyooo 1:d7ceb38da3d8 104
soyooo 1:d7ceb38da3d8 105 pidRobotX.allowable_error = 0.1;
soyooo 1:d7ceb38da3d8 106 pidRobotY.allowable_error = 0.1;
soyooo 1:d7ceb38da3d8 107 pidRobotYow.allowable_error = 2;
soyooo 1:d7ceb38da3d8 108 pidUss.allowable_error = 3;
soyooo 1:d7ceb38da3d8 109
TanakaTarou 0:6db16ad02a1b 110 while(1)
TanakaTarou 0:6db16ad02a1b 111 {
TanakaTarou 0:6db16ad02a1b 112 controller cmd = getPropoData(); //getPropoData & getCanData
TanakaTarou 0:6db16ad02a1b 113
TanakaTarou 0:6db16ad02a1b 114 static int posi_num = 0;
TanakaTarou 2:7af15d4ee55a 115 int angle_pid;
TanakaTarou 2:7af15d4ee55a 116 int velocity_pid;
TanakaTarou 2:7af15d4ee55a 117 can.read();
TanakaTarou 2:7af15d4ee55a 118 angle_pid = can.get(3, 1);
TanakaTarou 2:7af15d4ee55a 119 velocity_pid = can.get(3, 2);
soyooo 1:d7ceb38da3d8 120
soyooo 1:d7ceb38da3d8 121 if(position[posi_num][1] >= 10)
soyooo 1:d7ceb38da3d8 122 {
TanakaTarou 2:7af15d4ee55a 123 if(pidRobotX.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 124 && pidRobotYow.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 125 && pidUss.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 126 && velocity_pid == 1)
soyooo 1:d7ceb38da3d8 127 posi_num++;
soyooo 1:d7ceb38da3d8 128 }
TanakaTarou 2:7af15d4ee55a 129 else if(pidRobotX.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 130 && pidRobotYow.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 131 && pidRobotY.isConvergence(1) == 1
TanakaTarou 2:7af15d4ee55a 132 && velocity_pid == 1)
soyooo 1:d7ceb38da3d8 133 posi_num++;
soyooo 1:d7ceb38da3d8 134
TanakaTarou 2:7af15d4ee55a 135 if(posi_num >= 12)
soyooo 1:d7ceb38da3d8 136 posi_num = 0;
soyooo 1:d7ceb38da3d8 137
TanakaTarou 2:7af15d4ee55a 138 can.set(1, 1, position[posi_num][3]);
TanakaTarou 2:7af15d4ee55a 139 can.set(1, 2, int(position[posi_num][4]));
TanakaTarou 2:7af15d4ee55a 140 //can.set(2, 1, (position[posi_num][6]));
TanakaTarou 2:7af15d4ee55a 141 while(can.send() == 0);
TanakaTarou 0:6db16ad02a1b 142
TanakaTarou 0:6db16ad02a1b 143 //ロボットの移動速度(LX, LY, RX)
TanakaTarou 0:6db16ad02a1b 144 float robot_velocity[3];
TanakaTarou 0:6db16ad02a1b 145
TanakaTarou 0:6db16ad02a1b 146 //yow角調整処理
TanakaTarou 0:6db16ad02a1b 147 *pidRobotYow.target = position[posi_num][2];
TanakaTarou 0:6db16ad02a1b 148 robot_velocity[2] = pidRobotYow.output;
TanakaTarou 0:6db16ad02a1b 149
TanakaTarou 0:6db16ad02a1b 150 //x軸調整処理
TanakaTarou 0:6db16ad02a1b 151 *pidRobotX.target = position[posi_num][0];
TanakaTarou 0:6db16ad02a1b 152 robot_velocity[0] = pidRobotX.output;
TanakaTarou 0:6db16ad02a1b 153
TanakaTarou 0:6db16ad02a1b 154 //USS距離調整処理
soyooo 1:d7ceb38da3d8 155 if(position[posi_num][1] >= 10)
TanakaTarou 0:6db16ad02a1b 156 {
soyooo 1:d7ceb38da3d8 157 *pidUss.target = position[posi_num][1] - 10;
TanakaTarou 0:6db16ad02a1b 158 robot_velocity[1] = -pidUss.output;
TanakaTarou 0:6db16ad02a1b 159 }
TanakaTarou 0:6db16ad02a1b 160 else
TanakaTarou 0:6db16ad02a1b 161 {
TanakaTarou 0:6db16ad02a1b 162 //y軸調整処理
TanakaTarou 0:6db16ad02a1b 163 *pidRobotY.target = position[posi_num][1];
TanakaTarou 0:6db16ad02a1b 164 robot_velocity[1] = pidRobotY.output;
TanakaTarou 0:6db16ad02a1b 165 }
TanakaTarou 0:6db16ad02a1b 166
TanakaTarou 0:6db16ad02a1b 167 //角度・XYリセット
TanakaTarou 0:6db16ad02a1b 168 if(cmd.F == 2)
TanakaTarou 0:6db16ad02a1b 169 {
TanakaTarou 0:6db16ad02a1b 170 imu.angle[2] = 0;
TanakaTarou 0:6db16ad02a1b 171 *pidRobotYow.target = 0;
TanakaTarou 0:6db16ad02a1b 172 odm.x = 0;
TanakaTarou 0:6db16ad02a1b 173 *pidRobotX.target = 0;
TanakaTarou 0:6db16ad02a1b 174 odm.y = 0;
TanakaTarou 0:6db16ad02a1b 175 *pidRobotY.target = 0;
TanakaTarou 0:6db16ad02a1b 176 }
TanakaTarou 0:6db16ad02a1b 177
TanakaTarou 0:6db16ad02a1b 178 //ホイール速度計算
TanakaTarou 0:6db16ad02a1b 179 mecanum.setVelL(robot_velocity);
TanakaTarou 0:6db16ad02a1b 180 mecanum.computeWheelVel();
TanakaTarou 0:6db16ad02a1b 181 mecanum.rescaleWheelVel();
TanakaTarou 0:6db16ad02a1b 182
TanakaTarou 0:6db16ad02a1b 183 //モーターの駆動
TanakaTarou 0:6db16ad02a1b 184 for(int i = 0; i < 4; i++)
TanakaTarou 2:7af15d4ee55a 185 ;//Motor[i].drive(mecanum.wheel_vel[i]);
TanakaTarou 0:6db16ad02a1b 186
TanakaTarou 2:7af15d4ee55a 187 pc.printf("%d\t", angle_pid);
TanakaTarou 2:7af15d4ee55a 188 pc.printf("%d\t", velocity_pid);
soyooo 1:d7ceb38da3d8 189 pc.printf("%d\t", posi_num);
soyooo 1:d7ceb38da3d8 190
TanakaTarou 0:6db16ad02a1b 191 pc.printf("\n");
TanakaTarou 2:7af15d4ee55a 192
TanakaTarou 0:6db16ad02a1b 193 wait(0.02);
TanakaTarou 0:6db16ad02a1b 194 }
TanakaTarou 0:6db16ad02a1b 195 }
TanakaTarou 0:6db16ad02a1b 196
TanakaTarou 0:6db16ad02a1b 197 controller getPropoData()
TanakaTarou 0:6db16ad02a1b 198 {
TanakaTarou 0:6db16ad02a1b 199 float dead_zone = 0.05;
TanakaTarou 0:6db16ad02a1b 200 controller propo;
TanakaTarou 0:6db16ad02a1b 201 sbus.isFailSafe();
TanakaTarou 0:6db16ad02a1b 202
TanakaTarou 0:6db16ad02a1b 203 //propo直接コントロール
TanakaTarou 0:6db16ad02a1b 204 if(sbus.isFailSafe())
TanakaTarou 0:6db16ad02a1b 205 {
TanakaTarou 0:6db16ad02a1b 206 propo.LX = propo.LY = propo.RX = propo.RY = 0;
TanakaTarou 0:6db16ad02a1b 207 propo.H = propo.A = propo.D = propo.F = propo.G = propo.fail_safe = 0;
TanakaTarou 0:6db16ad02a1b 208 }
TanakaTarou 0:6db16ad02a1b 209 else
TanakaTarou 0:6db16ad02a1b 210 {
TanakaTarou 0:6db16ad02a1b 211 propo.LX = sbus.getStickVal(0) / 255.0;
TanakaTarou 0:6db16ad02a1b 212 propo.LY = sbus.getStickVal(1) / 255.0;
TanakaTarou 0:6db16ad02a1b 213 propo.RX = -sbus.getStickVal(2) / 255.0;
TanakaTarou 0:6db16ad02a1b 214 propo.RY = sbus.getStickVal(3) / 255.0;
TanakaTarou 0:6db16ad02a1b 215 propo.H = sbus.getSwitchVal(0);
TanakaTarou 0:6db16ad02a1b 216 propo.C = sbus.getSwitchVal(1);
TanakaTarou 0:6db16ad02a1b 217 propo.E = sbus.getSwitchVal(2);
TanakaTarou 0:6db16ad02a1b 218 propo.F = sbus.getSwitchVal(3);
TanakaTarou 0:6db16ad02a1b 219 propo.G = sbus.getSwitchVal(4);
TanakaTarou 0:6db16ad02a1b 220 propo.fail_safe = 1;
TanakaTarou 0:6db16ad02a1b 221 }
TanakaTarou 0:6db16ad02a1b 222
TanakaTarou 0:6db16ad02a1b 223 if(propo.RX < dead_zone && propo.RX > -dead_zone) propo.RX = 0;
TanakaTarou 0:6db16ad02a1b 224 if(propo.RY < dead_zone && propo.RY > -dead_zone) propo.RY = 0;
TanakaTarou 0:6db16ad02a1b 225 if(propo.LX < dead_zone && propo.LX > -dead_zone) propo.LX = 0;
TanakaTarou 0:6db16ad02a1b 226 if(propo.LY < dead_zone && propo.LY > -dead_zone) propo.LY = 0;
TanakaTarou 0:6db16ad02a1b 227 return propo;
TanakaTarou 0:6db16ad02a1b 228 }
TanakaTarou 0:6db16ad02a1b 229
TanakaTarou 0:6db16ad02a1b 230 /*
TanakaTarou 0:6db16ad02a1b 231 bool isConvergence(int num)
TanakaTarou 0:6db16ad02a1b 232 {
TanakaTarou 0:6db16ad02a1b 233 bool tf;
TanakaTarou 0:6db16ad02a1b 234 if(num > 3 && num < 8)
TanakaTarou 0:6db16ad02a1b 235 num -= 4;
TanakaTarou 0:6db16ad02a1b 236 else if(num > 7 && num < 12)
TanakaTarou 0:6db16ad02a1b 237 num -= 8;
TanakaTarou 0:6db16ad02a1b 238 else if(num > 11 && num < 15)
TanakaTarou 0:6db16ad02a1b 239 num -= 8;
TanakaTarou 0:6db16ad02a1b 240
TanakaTarou 0:6db16ad02a1b 241 if(num == 0)
TanakaTarou 0:6db16ad02a1b 242 {
TanakaTarou 0:6db16ad02a1b 243 if(pidRobotX.output == 0)
TanakaTarou 0:6db16ad02a1b 244 tf = 1;
TanakaTarou 0:6db16ad02a1b 245 else
TanakaTarou 0:6db16ad02a1b 246 tf = 0;
TanakaTarou 0:6db16ad02a1b 247 }
TanakaTarou 0:6db16ad02a1b 248 else if(num == 1)
TanakaTarou 0:6db16ad02a1b 249 {
TanakaTarou 0:6db16ad02a1b 250 if(pidUss.output == 0)
TanakaTarou 0:6db16ad02a1b 251 tf = 1;
TanakaTarou 0:6db16ad02a1b 252 else
TanakaTarou 0:6db16ad02a1b 253 tf = 0;
TanakaTarou 0:6db16ad02a1b 254 }
TanakaTarou 0:6db16ad02a1b 255 else if(num == 2)
TanakaTarou 0:6db16ad02a1b 256 {
TanakaTarou 0:6db16ad02a1b 257 wait(1.0);
TanakaTarou 0:6db16ad02a1b 258 tf = 1;
TanakaTarou 0:6db16ad02a1b 259 }
TanakaTarou 0:6db16ad02a1b 260 else if(num == 3)
TanakaTarou 0:6db16ad02a1b 261 {
TanakaTarou 0:6db16ad02a1b 262 if(pidRobotY.output == 0)
TanakaTarou 0:6db16ad02a1b 263 tf = 1;
TanakaTarou 0:6db16ad02a1b 264 else
TanakaTarou 0:6db16ad02a1b 265 tf = 0;
TanakaTarou 0:6db16ad02a1b 266 }
TanakaTarou 0:6db16ad02a1b 267 else if(num == 15)
TanakaTarou 0:6db16ad02a1b 268 {
TanakaTarou 0:6db16ad02a1b 269
TanakaTarou 0:6db16ad02a1b 270 }
TanakaTarou 0:6db16ad02a1b 271 else if(num == 16)
TanakaTarou 0:6db16ad02a1b 272 {
TanakaTarou 0:6db16ad02a1b 273
TanakaTarou 0:6db16ad02a1b 274 }
TanakaTarou 0:6db16ad02a1b 275 else if(num == 17)
TanakaTarou 0:6db16ad02a1b 276 {
TanakaTarou 0:6db16ad02a1b 277
TanakaTarou 0:6db16ad02a1b 278 }
TanakaTarou 0:6db16ad02a1b 279
TanakaTarou 0:6db16ad02a1b 280 return tf;
TanakaTarou 0:6db16ad02a1b 281 }
TanakaTarou 0:6db16ad02a1b 282 */