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.
main.cpp@9:e248986c8423, 2019-05-01 (annotated)
- Committer:
- yuto17320508
- Date:
- Wed May 01 08:13:24 2019 +0000
- Revision:
- 9:e248986c8423
- Parent:
- 8:ded0354412ae
- Child:
- 10:a335588b9ef0
l
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
eri | 0:c1476d342c13 | 1 | #include "mbed.h" |
eri | 0:c1476d342c13 | 2 | #include "pin.h" |
eri | 0:c1476d342c13 | 3 | #include "microinfinity.h" |
eri | 0:c1476d342c13 | 4 | |
yuto17320508 | 4:81f01f93e502 | 5 | //#define DEBUG_ON |
yuto17320508 | 4:81f01f93e502 | 6 | |
yuto17320508 | 4:81f01f93e502 | 7 | #ifdef DEBUG_ON |
yuto17320508 | 4:81f01f93e502 | 8 | #define DEBUG(...) printf("" __VA_ARGS__); |
yuto17320508 | 4:81f01f93e502 | 9 | #else |
yuto17320508 | 4:81f01f93e502 | 10 | #define DEBUG(...) |
yuto17320508 | 4:81f01f93e502 | 11 | #endif |
yuto17320508 | 4:81f01f93e502 | 12 | |
yuto17320508 | 4:81f01f93e502 | 13 | #define Pi 3.14159265359 //円周率π |
yuto17320508 | 4:81f01f93e502 | 14 | |
yuto17320508 | 4:81f01f93e502 | 15 | float accel_max = 0.01; //これグローバルにしたのはごめん。set関数多すぎてめんどくなった。 |
yuto17320508 | 4:81f01f93e502 | 16 | |
yuto17320508 | 4:81f01f93e502 | 17 | class PIDcontroller //distanceをvalueに置き換えました |
yuto17320508 | 4:81f01f93e502 | 18 | { |
yuto17320508 | 4:81f01f93e502 | 19 | float Kp_, Ki_, Kd_, tolerance_, time_delta_; |
yuto17320508 | 4:81f01f93e502 | 20 | float pile_, value_old_, target_; |
yuto17320508 | 4:81f01f93e502 | 21 | |
yuto17320508 | 5:63462d696256 | 22 | public: |
yuto17320508 | 4:81f01f93e502 | 23 | bool IsConvergence_; //収束したかどうか |
yuto17320508 | 4:81f01f93e502 | 24 | PIDcontroller(float Kp, float Ki, float Kd); //初期設定で係数を入力 |
yuto17320508 | 5:63462d696256 | 25 | void setCoefficients(float Kp, float Ki, float Kd) |
yuto17320508 | 5:63462d696256 | 26 | { |
yuto17320508 | 5:63462d696256 | 27 | Kp_ = Kp, Ki_ = Ki, Kd_ = Kd; |
yuto17320508 | 5:63462d696256 | 28 | }; //係数を変更するときに使う |
yuto17320508 | 5:63462d696256 | 29 | void setTimeDelta(float delta) |
yuto17320508 | 5:63462d696256 | 30 | { |
yuto17320508 | 5:63462d696256 | 31 | time_delta_ = delta; |
yuto17320508 | 5:63462d696256 | 32 | }; |
yuto17320508 | 4:81f01f93e502 | 33 | void setTarget(float target); //目標位置の設定 |
yuto17320508 | 5:63462d696256 | 34 | void setTolerance(float tolerance) |
yuto17320508 | 5:63462d696256 | 35 | { |
yuto17320508 | 5:63462d696256 | 36 | tolerance_ = tolerance; |
yuto17320508 | 5:63462d696256 | 37 | }; //許容誤差の設定 |
yuto17320508 | 4:81f01f93e502 | 38 | float calc(float nowVal); //現在位置と目標を比較してPID補正 |
yuto17320508 | 5:63462d696256 | 39 | bool knowConvergence() |
yuto17320508 | 5:63462d696256 | 40 | { |
yuto17320508 | 5:63462d696256 | 41 | return IsConvergence_; |
yuto17320508 | 5:63462d696256 | 42 | }; //収束したかどうかを外部に伝える |
yuto17320508 | 4:81f01f93e502 | 43 | }; |
yuto17320508 | 4:81f01f93e502 | 44 | |
yuto17320508 | 4:81f01f93e502 | 45 | class Motor //PIDコントローラ、エンコーダを含むモータのクラス |
yuto17320508 | 4:81f01f93e502 | 46 | { |
yuto17320508 | 4:81f01f93e502 | 47 | PwmOut *pin_forward_, *pin_back_; |
yuto17320508 | 4:81f01f93e502 | 48 | Ec *ec_; //対応するエンコーダ |
yuto17320508 | 4:81f01f93e502 | 49 | float duty_, pre_duty_, duty_limit_; //dutyと現在のモータ位置 |
yuto17320508 | 4:81f01f93e502 | 50 | int resolution_; |
yuto17320508 | 5:63462d696256 | 51 | public: |
yuto17320508 | 4:81f01f93e502 | 52 | Motor(PwmOut *forward, PwmOut *back); //ピンをポインタ渡し |
yuto17320508 | 5:63462d696256 | 53 | void setDutyLimit(float limit) |
yuto17320508 | 5:63462d696256 | 54 | { |
yuto17320508 | 5:63462d696256 | 55 | duty_limit_ = limit; |
yuto17320508 | 5:63462d696256 | 56 | }; |
yuto17320508 | 4:81f01f93e502 | 57 | float getPosi(); //ポジをエンコーダから取得 |
yuto17320508 | 4:81f01f93e502 | 58 | void calcDuty(PIDcontroller *pid); //Duty比を計算 |
yuto17320508 | 5:63462d696256 | 59 | void setEncoder(Ec *ec) |
yuto17320508 | 5:63462d696256 | 60 | { |
yuto17320508 | 5:63462d696256 | 61 | ec_ = ec; |
yuto17320508 | 5:63462d696256 | 62 | }; //エンコーダを設定 |
yuto17320508 | 5:63462d696256 | 63 | void setResolution(int reso) |
yuto17320508 | 5:63462d696256 | 64 | { |
yuto17320508 | 5:63462d696256 | 65 | resolution_ = reso; |
yuto17320508 | 5:63462d696256 | 66 | }; |
yuto17320508 | 4:81f01f93e502 | 67 | void output(); //出力するだけ |
yuto17320508 | 4:81f01f93e502 | 68 | void output(float duty); |
yuto17320508 | 4:81f01f93e502 | 69 | }; |
yuto17320508 | 4:81f01f93e502 | 70 | |
yuto17320508 | 4:81f01f93e502 | 71 | class OneLeg //足の挙動を制御する |
yuto17320508 | 4:81f01f93e502 | 72 | { |
yuto17320508 | 4:81f01f93e502 | 73 | Motor *motor_; |
yuto17320508 | 4:81f01f93e502 | 74 | float target_pose_; |
yuto17320508 | 4:81f01f93e502 | 75 | |
yuto17320508 | 5:63462d696256 | 76 | public: |
yuto17320508 | 4:81f01f93e502 | 77 | PIDcontroller *pid_; |
yuto17320508 | 5:63462d696256 | 78 | OneLeg() {}; |
yuto17320508 | 5:63462d696256 | 79 | void setMotor(Motor *motor) |
yuto17320508 | 5:63462d696256 | 80 | { |
yuto17320508 | 5:63462d696256 | 81 | motor_ = motor; |
yuto17320508 | 5:63462d696256 | 82 | }; |
yuto17320508 | 5:63462d696256 | 83 | void setPIDcontroller(PIDcontroller *pid) |
yuto17320508 | 5:63462d696256 | 84 | { |
yuto17320508 | 5:63462d696256 | 85 | pid_ = pid; |
yuto17320508 | 5:63462d696256 | 86 | }; |
yuto17320508 | 4:81f01f93e502 | 87 | void setTargetPose(float target_pose); |
yuto17320508 | 4:81f01f93e502 | 88 | void actMotor();//モータ出力 |
yuto17320508 | 4:81f01f93e502 | 89 | }; |
yuto17320508 | 4:81f01f93e502 | 90 | |
yuto17320508 | 4:81f01f93e502 | 91 | class Robot |
yuto17320508 | 4:81f01f93e502 | 92 | { |
yuto17320508 | 4:81f01f93e502 | 93 | float ticker_time_, air_wait_time_; |
yuto17320508 | 4:81f01f93e502 | 94 | OneLeg *Leg1_, *Leg2_; |
yuto17320508 | 4:81f01f93e502 | 95 | Timer timer; |
yuto17320508 | 4:81f01f93e502 | 96 | |
yuto17320508 | 5:63462d696256 | 97 | public: |
yuto17320508 | 5:63462d696256 | 98 | Robot() |
yuto17320508 | 5:63462d696256 | 99 | { |
yuto17320508 | 5:63462d696256 | 100 | timer.reset(); |
yuto17320508 | 5:63462d696256 | 101 | timer.start(); |
yuto17320508 | 5:63462d696256 | 102 | }; |
yuto17320508 | 4:81f01f93e502 | 103 | void setLeg(OneLeg *Leg1_, OneLeg *Leg2_); |
yuto17320508 | 4:81f01f93e502 | 104 | void setTickerTime(float ticker_time); |
yuto17320508 | 4:81f01f93e502 | 105 | void run();//ここがメインで走る記述 |
yuto17320508 | 4:81f01f93e502 | 106 | }; |
yuto17320508 | 4:81f01f93e502 | 107 | |
yuto17320508 | 4:81f01f93e502 | 108 | |
yuto17320508 | 4:81f01f93e502 | 109 | |
yuto17320508 | 4:81f01f93e502 | 110 | PIDcontroller::PIDcontroller(float Kp, float Ki, float Kd) |
yuto17320508 | 4:81f01f93e502 | 111 | { |
yuto17320508 | 4:81f01f93e502 | 112 | Kp_ = Kp, Ki_ = Ki, Kd_ = Kd; |
yuto17320508 | 4:81f01f93e502 | 113 | DEBUG("set Kp:%.3f KI:%.3f Kd:%.3f \n\r", Kp_, Ki_, Kd_); |
yuto17320508 | 4:81f01f93e502 | 114 | IsConvergence_=true; |
yuto17320508 | 4:81f01f93e502 | 115 | } |
yuto17320508 | 4:81f01f93e502 | 116 | void PIDcontroller::setTarget(float target) |
yuto17320508 | 4:81f01f93e502 | 117 | { |
yuto17320508 | 5:63462d696256 | 118 | if (IsConvergence_) { //収束時のみ変更可能 |
yuto17320508 | 4:81f01f93e502 | 119 | target_ = target; |
yuto17320508 | 4:81f01f93e502 | 120 | DEBUG("set Target: %.3f\n\r", target_); |
yuto17320508 | 4:81f01f93e502 | 121 | IsConvergence_ = false; |
yuto17320508 | 5:63462d696256 | 122 | } else { |
yuto17320508 | 4:81f01f93e502 | 123 | DEBUG("error: setTarget permission denied!\n"); |
yuto17320508 | 4:81f01f93e502 | 124 | } |
yuto17320508 | 4:81f01f93e502 | 125 | } |
yuto17320508 | 4:81f01f93e502 | 126 | float PIDcontroller::calc(float nowVal) |
yuto17320508 | 4:81f01f93e502 | 127 | { |
yuto17320508 | 4:81f01f93e502 | 128 | float out = 0; |
yuto17320508 | 4:81f01f93e502 | 129 | //PID計算ここで行う |
yuto17320508 | 4:81f01f93e502 | 130 | float deviation = target_ - nowVal; //目標との差分 |
yuto17320508 | 4:81f01f93e502 | 131 | pile_ += deviation; //積分用に和を取る |
yuto17320508 | 4:81f01f93e502 | 132 | out = deviation * Kp_ - (nowVal - value_old_) / time_delta_ * Kd_ + pile_ * Ki_ * time_delta_; |
yuto17320508 | 4:81f01f93e502 | 133 | value_old_ = nowVal; //今のデータを保存 |
yuto17320508 | 4:81f01f93e502 | 134 | // |
yuto17320508 | 5:63462d696256 | 135 | if (fabs(deviation) < tolerance_) { //収束した場合 |
yuto17320508 | 4:81f01f93e502 | 136 | DEBUG("complete !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n\r"); |
yuto17320508 | 4:81f01f93e502 | 137 | out = 0; |
yuto17320508 | 4:81f01f93e502 | 138 | pile_ = 0; |
yuto17320508 | 4:81f01f93e502 | 139 | value_old_ = 0; |
yuto17320508 | 4:81f01f93e502 | 140 | IsConvergence_ = true; |
yuto17320508 | 4:81f01f93e502 | 141 | } |
yuto17320508 | 4:81f01f93e502 | 142 | return out; |
yuto17320508 | 4:81f01f93e502 | 143 | } |
yuto17320508 | 4:81f01f93e502 | 144 | |
yuto17320508 | 4:81f01f93e502 | 145 | Motor::Motor(PwmOut *forward, PwmOut *back) |
yuto17320508 | 4:81f01f93e502 | 146 | { |
yuto17320508 | 4:81f01f93e502 | 147 | pin_forward_ = forward; |
yuto17320508 | 4:81f01f93e502 | 148 | pin_back_ = back; |
yuto17320508 | 4:81f01f93e502 | 149 | } |
yuto17320508 | 4:81f01f93e502 | 150 | float Motor::getPosi() |
yuto17320508 | 4:81f01f93e502 | 151 | { |
yuto17320508 | 4:81f01f93e502 | 152 | float posi = 2.0*180*((float)(ec_->getCount)()/(float)resolution_); |
yuto17320508 | 5:63462d696256 | 153 | |
yuto17320508 | 4:81f01f93e502 | 154 | //DEBUG("value :%d :%d\n\r", (ec_->getCount)(),resolution_); |
yuto17320508 | 4:81f01f93e502 | 155 | DEBUG("posi is %.4f\n\r",posi); |
yuto17320508 | 4:81f01f93e502 | 156 | return posi; |
yuto17320508 | 4:81f01f93e502 | 157 | } |
yuto17320508 | 4:81f01f93e502 | 158 | void Motor::calcDuty(PIDcontroller *pid) |
yuto17320508 | 5:63462d696256 | 159 | { |
yuto17320508 | 4:81f01f93e502 | 160 | duty_ = pid->calc(getPosi()); |
yuto17320508 | 4:81f01f93e502 | 161 | DEBUG("duty is %.4f\n\r",duty_); |
yuto17320508 | 4:81f01f93e502 | 162 | } |
yuto17320508 | 4:81f01f93e502 | 163 | void Motor::output() |
yuto17320508 | 4:81f01f93e502 | 164 | { |
yuto17320508 | 4:81f01f93e502 | 165 | //DEBUG("dutyOut %.3f\n\r",duty_); |
yuto17320508 | 4:81f01f93e502 | 166 | //加速度が一定値を超えたら変更加える |
yuto17320508 | 5:63462d696256 | 167 | if (duty_ > 0) { |
yuto17320508 | 4:81f01f93e502 | 168 | if (duty_ - pre_duty_ > accel_max) duty_ = pre_duty_ + accel_max; |
yuto17320508 | 4:81f01f93e502 | 169 | double output_duty=min(fabs(duty_), duty_limit_); |
yuto17320508 | 4:81f01f93e502 | 170 | pin_forward_->write(output_duty); |
yuto17320508 | 4:81f01f93e502 | 171 | pin_back_->write(0); |
yuto17320508 | 4:81f01f93e502 | 172 | DEBUG("forward %.3f\n\r",pin_forward_->read()); |
yuto17320508 | 5:63462d696256 | 173 | } else { |
yuto17320508 | 4:81f01f93e502 | 174 | if (pre_duty_ - duty_ > accel_max) |
yuto17320508 | 4:81f01f93e502 | 175 | duty_ = pre_duty_ - accel_max; |
yuto17320508 | 4:81f01f93e502 | 176 | double output_duty=min(fabs(duty_), duty_limit_); |
yuto17320508 | 4:81f01f93e502 | 177 | pin_forward_->write(0); |
yuto17320508 | 4:81f01f93e502 | 178 | pin_back_->write(output_duty); |
yuto17320508 | 4:81f01f93e502 | 179 | DEBUG("back %.3f\n\r",pin_back_->read()); |
yuto17320508 | 4:81f01f93e502 | 180 | } |
yuto17320508 | 4:81f01f93e502 | 181 | pre_duty_ = duty_; |
yuto17320508 | 4:81f01f93e502 | 182 | } |
yuto17320508 | 4:81f01f93e502 | 183 | void Motor::output(float duty) |
yuto17320508 | 4:81f01f93e502 | 184 | { |
yuto17320508 | 4:81f01f93e502 | 185 | duty_ = duty; |
yuto17320508 | 4:81f01f93e502 | 186 | //DEBUG("dutyOut %.3f\n\r",duty_); |
yuto17320508 | 4:81f01f93e502 | 187 | //加速度が一定値を超えたら変更加える |
yuto17320508 | 5:63462d696256 | 188 | if (duty_ > 0) { |
yuto17320508 | 4:81f01f93e502 | 189 | //if (duty_ - pre_duty_ > accel_max) duty_ = pre_duty_ + accel_max; |
yuto17320508 | 4:81f01f93e502 | 190 | double output_duty=min(fabs(duty_), duty_limit_); |
yuto17320508 | 4:81f01f93e502 | 191 | pin_forward_->write(output_duty); |
yuto17320508 | 4:81f01f93e502 | 192 | pin_back_->write(0); |
yuto17320508 | 4:81f01f93e502 | 193 | DEBUG("forward %.3f\n\r",pin_forward_->read()); |
yuto17320508 | 5:63462d696256 | 194 | } else { |
yuto17320508 | 4:81f01f93e502 | 195 | //if (pre_duty_ - duty_ > accel_max) |
yuto17320508 | 4:81f01f93e502 | 196 | // duty_ = pre_duty_ - accel_max; |
yuto17320508 | 4:81f01f93e502 | 197 | double output_duty=min(fabs(duty_), duty_limit_); |
yuto17320508 | 4:81f01f93e502 | 198 | pin_forward_->write(0); |
yuto17320508 | 4:81f01f93e502 | 199 | pin_back_->write(output_duty); |
yuto17320508 | 4:81f01f93e502 | 200 | DEBUG("back %.3f\n\r",pin_back_->read()); |
yuto17320508 | 4:81f01f93e502 | 201 | } |
yuto17320508 | 4:81f01f93e502 | 202 | pre_duty_ = duty_; |
yuto17320508 | 4:81f01f93e502 | 203 | } |
yuto17320508 | 4:81f01f93e502 | 204 | |
yuto17320508 | 4:81f01f93e502 | 205 | void OneLeg::setTargetPose(float target_pose) |
yuto17320508 | 4:81f01f93e502 | 206 | { |
yuto17320508 | 4:81f01f93e502 | 207 | target_pose_ = target_pose; |
yuto17320508 | 4:81f01f93e502 | 208 | //PIDにtargetを送る |
yuto17320508 | 4:81f01f93e502 | 209 | pid_->setTarget(target_pose_); |
yuto17320508 | 4:81f01f93e502 | 210 | } |
yuto17320508 | 4:81f01f93e502 | 211 | void OneLeg::actMotor() |
yuto17320508 | 4:81f01f93e502 | 212 | { |
yuto17320508 | 4:81f01f93e502 | 213 | motor_->calcDuty(pid_); |
yuto17320508 | 4:81f01f93e502 | 214 | motor_->output(); |
yuto17320508 | 4:81f01f93e502 | 215 | } |
yuto17320508 | 4:81f01f93e502 | 216 | |
yuto17320508 | 4:81f01f93e502 | 217 | |
yuto17320508 | 4:81f01f93e502 | 218 | |
yuto17320508 | 4:81f01f93e502 | 219 | void Robot::setLeg(OneLeg *Leg1, OneLeg *Leg2) |
yuto17320508 | 4:81f01f93e502 | 220 | { |
yuto17320508 | 4:81f01f93e502 | 221 | Leg1_ = Leg1; |
yuto17320508 | 4:81f01f93e502 | 222 | Leg2_ = Leg2; |
yuto17320508 | 4:81f01f93e502 | 223 | } |
yuto17320508 | 4:81f01f93e502 | 224 | void Robot::setTickerTime(float ticker_time) |
yuto17320508 | 4:81f01f93e502 | 225 | { |
yuto17320508 | 4:81f01f93e502 | 226 | ticker_time_ = ticker_time; |
yuto17320508 | 4:81f01f93e502 | 227 | Leg1_->pid_->setTimeDelta(ticker_time_); |
yuto17320508 | 4:81f01f93e502 | 228 | Leg2_->pid_->setTimeDelta(ticker_time_); |
yuto17320508 | 4:81f01f93e502 | 229 | } |
yuto17320508 | 4:81f01f93e502 | 230 | void Robot::run() |
yuto17320508 | 4:81f01f93e502 | 231 | { |
yuto17320508 | 5:63462d696256 | 232 | while (!Leg1_->pid_->IsConvergence_ || !Leg2_->pid_->IsConvergence_) { //片方が収束していない時*/ |
yuto17320508 | 4:81f01f93e502 | 233 | //ticker_time毎にモータに出力する |
yuto17320508 | 4:81f01f93e502 | 234 | float time_s = timer.read(); |
yuto17320508 | 4:81f01f93e502 | 235 | Leg1_->actMotor(); |
yuto17320508 | 4:81f01f93e502 | 236 | Leg2_->actMotor(); |
yuto17320508 | 4:81f01f93e502 | 237 | float rest_time_s = ticker_time_ - (timer.read() - time_s); |
yuto17320508 | 4:81f01f93e502 | 238 | //ticker_timeまで待機 |
yuto17320508 | 5:63462d696256 | 239 | if (rest_time_s > 0) { |
yuto17320508 | 4:81f01f93e502 | 240 | wait(rest_time_s); |
yuto17320508 | 4:81f01f93e502 | 241 | DEBUG("start:%.3f last: %.3f restTime: %.3f\n\r",time_s, timer.read(),rest_time_s); |
yuto17320508 | 4:81f01f93e502 | 242 | } |
yuto17320508 | 5:63462d696256 | 243 | |
yuto17320508 | 4:81f01f93e502 | 244 | else //時間が足りない場合警告 |
yuto17320508 | 4:81f01f93e502 | 245 | printf("error: restTime not enough\n\r"); |
yuto17320508 | 4:81f01f93e502 | 246 | DEBUG("loop end\n\r") |
yuto17320508 | 4:81f01f93e502 | 247 | } |
yuto17320508 | 4:81f01f93e502 | 248 | |
yuto17320508 | 4:81f01f93e502 | 249 | } |
yuto17320508 | 4:81f01f93e502 | 250 | |
eri | 0:c1476d342c13 | 251 | |
eri | 0:c1476d342c13 | 252 | |
eri | 0:c1476d342c13 | 253 | ////////////関数 |
yuto17320508 | 4:81f01f93e502 | 254 | void reset(); |
eri | 0:c1476d342c13 | 255 | void setup(); |
yuto17320508 | 4:81f01f93e502 | 256 | void can_send(float target_ro, float target_ri); |
yuto17320508 | 5:63462d696256 | 257 | void straight(int &step_num_l, int &step_num_r); |
yuto17320508 | 5:63462d696256 | 258 | void turnLeft(int &step_num_l, int &step_num_r); |
yuto17320508 | 5:63462d696256 | 259 | void turnRight(int &step_num_l, int &step_num_r); |
eri | 0:c1476d342c13 | 260 | |
eri | 0:c1476d342c13 | 261 | ////////////定数 |
eri | 0:c1476d342c13 | 262 | |
eri | 0:c1476d342c13 | 263 | ////////////変数 |
eri | 0:c1476d342c13 | 264 | bool hand_mode=0; |
kageyuta | 1:86c4c38abe40 | 265 | |
yuto17320508 | 4:81f01f93e502 | 266 | //PIDcontroller, Motor, AirCylinderはOneLegのメンバクラスとして扱う |
yuto17320508 | 4:81f01f93e502 | 267 | //しかし変更を多々行うためポインタ渡しにしてある |
yuto17320508 | 4:81f01f93e502 | 268 | //文が長くなると困るため, PID係数の変更は直接PIDコントローラを介して行う |
yuto17320508 | 4:81f01f93e502 | 269 | PIDcontroller pid_lo(0.01, 0.000, 0.000); |
yuto17320508 | 4:81f01f93e502 | 270 | PIDcontroller pid_li(0.01, 0.000, 0.000); //Kp.Ki,Kd |
yuto17320508 | 4:81f01f93e502 | 271 | Motor motor_lo(&motor_lo_f, &motor_lo_b), |
yuto17320508 | 5:63462d696256 | 272 | motor_li(&motor_li_f, &motor_li_b); //forward,backのピンを代入 |
yuto17320508 | 4:81f01f93e502 | 273 | OneLeg leg_lo, leg_li; |
yuto17320508 | 4:81f01f93e502 | 274 | Robot robot; |
eri | 0:c1476d342c13 | 275 | |
eri | 0:c1476d342c13 | 276 | ///////////////////////////////////////////// |
kageyuta | 1:86c4c38abe40 | 277 | int main() |
kageyuta | 1:86c4c38abe40 | 278 | { |
eri | 0:c1476d342c13 | 279 | setup(); |
yuto17320508 | 5:63462d696256 | 280 | |
kageyuta | 6:fe9fa8c2e6f9 | 281 | |
kageyuta | 6:fe9fa8c2e6f9 | 282 | |
yuto17320508 | 4:81f01f93e502 | 283 | pid_lo.setTolerance(10); |
yuto17320508 | 4:81f01f93e502 | 284 | pid_li.setTolerance(10); |
yuto17320508 | 5:63462d696256 | 285 | |
yuto17320508 | 4:81f01f93e502 | 286 | motor_lo.setEncoder(&ec_lo); |
yuto17320508 | 4:81f01f93e502 | 287 | motor_lo.setResolution(1000); |
yuto17320508 | 4:81f01f93e502 | 288 | motor_li.setEncoder(&ec_li); |
yuto17320508 | 7:cff25545558f | 289 | motor_li.setResolution(600); |
yuto17320508 | 5:63462d696256 | 290 | |
yuto17320508 | 4:81f01f93e502 | 291 | leg_lo.setMotor(&motor_lo); |
yuto17320508 | 4:81f01f93e502 | 292 | leg_lo.setPIDcontroller(&pid_lo); |
yuto17320508 | 4:81f01f93e502 | 293 | leg_li.setMotor(&motor_li); |
yuto17320508 | 4:81f01f93e502 | 294 | leg_li.setPIDcontroller(&pid_li); |
yuto17320508 | 5:63462d696256 | 295 | |
yuto17320508 | 4:81f01f93e502 | 296 | robot.setLeg(&leg_lo, &leg_li); |
yuto17320508 | 4:81f01f93e502 | 297 | robot.setTickerTime(0.01); //モータ出力間隔 0.01 |
yuto17320508 | 5:63462d696256 | 298 | |
yuto17320508 | 9:e248986c8423 | 299 | motor_lo.setDutyLimit(0.5); |
yuto17320508 | 9:e248986c8423 | 300 | motor_li.setDutyLimit(0.5); |
yuto17320508 | 5:63462d696256 | 301 | |
yuto17320508 | 4:81f01f93e502 | 302 | /* |
yuto17320508 | 4:81f01f93e502 | 303 | char str[255] = {}; |
yuto17320508 | 4:81f01f93e502 | 304 | printf("setup complete Input any key\n\r"); |
yuto17320508 | 4:81f01f93e502 | 305 | scanf("%s", str); |
yuto17320508 | 4:81f01f93e502 | 306 | printf("start!"); |
yuto17320508 | 4:81f01f93e502 | 307 | */ |
yuto17320508 | 5:63462d696256 | 308 | |
kageyuta | 6:fe9fa8c2e6f9 | 309 | |
kageyuta | 6:fe9fa8c2e6f9 | 310 | |
kageyuta | 6:fe9fa8c2e6f9 | 311 | |
kageyuta | 6:fe9fa8c2e6f9 | 312 | |
kageyuta | 2:55c616d2e0fe | 313 | reset(); |
yuto17320508 | 4:81f01f93e502 | 314 | printf("bus standby\n\r"); |
yuto17320508 | 5:63462d696256 | 315 | while(1) { |
yuto17320508 | 5:63462d696256 | 316 | if(bus_in.read() == 1) break; |
yuto17320508 | 3:7a608fbd3bcd | 317 | } |
yuto17320508 | 4:81f01f93e502 | 318 | printf("bus is %d\n\r", bus_in.read()); |
yuto17320508 | 5:63462d696256 | 319 | |
yuto17320508 | 4:81f01f93e502 | 320 | //Sample |
yuto17320508 | 5:63462d696256 | 321 | static int step_num_l = 0, step_num_r = 0; |
yuto17320508 | 5:63462d696256 | 322 | |
yuto17320508 | 5:63462d696256 | 323 | while(1) |
yuto17320508 | 4:81f01f93e502 | 324 | { |
yuto17320508 | 9:e248986c8423 | 325 | //straight(step_num_l, step_num_r); |
yuto17320508 | 9:e248986c8423 | 326 | turnLeft(step_num_l, step_num_r); |
yuto17320508 | 5:63462d696256 | 327 | //printf("machine degree:%.3f\r\n", degree0); |
kageyuta | 6:fe9fa8c2e6f9 | 328 | wait(0.01); |
yuto17320508 | 3:7a608fbd3bcd | 329 | } |
yuto17320508 | 4:81f01f93e502 | 330 | |
yuto17320508 | 5:63462d696256 | 331 | //turnLeft(step_num_l, step_num_r); |
yuto17320508 | 5:63462d696256 | 332 | //turnRight(step_num_l, step_num_r); |
yuto17320508 | 5:63462d696256 | 333 | } |
yuto17320508 | 5:63462d696256 | 334 | void straight(int &step_num_l, int &step_num_r) |
yuto17320508 | 5:63462d696256 | 335 | { |
yuto17320508 | 7:cff25545558f | 336 | can_send((float)step_num_r,(float)step_num_r); |
yuto17320508 | 5:63462d696256 | 337 | leg_lo.setTargetPose(360+step_num_l*180); |
yuto17320508 | 5:63462d696256 | 338 | leg_li.setTargetPose(180+step_num_l*180); |
yuto17320508 | 5:63462d696256 | 339 | robot.run(); |
yuto17320508 | 4:81f01f93e502 | 340 | motor_lo_f.write(0); |
yuto17320508 | 4:81f01f93e502 | 341 | motor_lo_b.write(0); |
yuto17320508 | 4:81f01f93e502 | 342 | motor_li_f.write(0); |
yuto17320508 | 4:81f01f93e502 | 343 | motor_li_b.write(0); |
yuto17320508 | 5:63462d696256 | 344 | while(1) { |
yuto17320508 | 5:63462d696256 | 345 | if(bus_in.read() == 1) break; |
yuto17320508 | 5:63462d696256 | 346 | } |
yuto17320508 | 7:cff25545558f | 347 | step_num_l++; |
yuto17320508 | 7:cff25545558f | 348 | step_num_r++; |
yuto17320508 | 5:63462d696256 | 349 | } |
yuto17320508 | 5:63462d696256 | 350 | void turnLeft(int &step_num_l, int &step_num_r) |
yuto17320508 | 5:63462d696256 | 351 | { |
yuto17320508 | 8:ded0354412ae | 352 | can_send(step_num_r,step_num_r); |
yuto17320508 | 5:63462d696256 | 353 | leg_lo.setTargetPose(360+(step_num_l-2)*180); |
yuto17320508 | 5:63462d696256 | 354 | leg_li.setTargetPose(180+(step_num_l-2)*180); |
yuto17320508 | 5:63462d696256 | 355 | robot.run(); |
yuto17320508 | 5:63462d696256 | 356 | motor_lo_f.write(0); |
yuto17320508 | 5:63462d696256 | 357 | motor_lo_b.write(0); |
yuto17320508 | 5:63462d696256 | 358 | motor_li_f.write(0); |
yuto17320508 | 5:63462d696256 | 359 | motor_li_b.write(0); |
yuto17320508 | 5:63462d696256 | 360 | while(1) { |
yuto17320508 | 5:63462d696256 | 361 | if(bus_in.read() == 1) break; |
yuto17320508 | 5:63462d696256 | 362 | } |
yuto17320508 | 5:63462d696256 | 363 | step_num_r++; |
yuto17320508 | 5:63462d696256 | 364 | step_num_l--; |
yuto17320508 | 5:63462d696256 | 365 | } |
yuto17320508 | 5:63462d696256 | 366 | void turnRight(int &step_num_l, int &step_num_r) |
yuto17320508 | 5:63462d696256 | 367 | { |
yuto17320508 | 8:ded0354412ae | 368 | can_send(step_num_r-2,step_num_r-2); |
yuto17320508 | 8:ded0354412ae | 369 | leg_lo.setTargetPose(360+step_num_l*180); |
yuto17320508 | 8:ded0354412ae | 370 | leg_li.setTargetPose(180+step_num_l*180); |
yuto17320508 | 5:63462d696256 | 371 | robot.run(); |
yuto17320508 | 5:63462d696256 | 372 | motor_lo_f.write(0); |
yuto17320508 | 5:63462d696256 | 373 | motor_lo_b.write(0); |
yuto17320508 | 5:63462d696256 | 374 | motor_li_f.write(0); |
yuto17320508 | 5:63462d696256 | 375 | motor_li_b.write(0); |
yuto17320508 | 5:63462d696256 | 376 | while(1) { |
yuto17320508 | 5:63462d696256 | 377 | if(bus_in.read() == 1) break; |
yuto17320508 | 5:63462d696256 | 378 | } |
yuto17320508 | 8:ded0354412ae | 379 | step_num_r--; |
yuto17320508 | 8:ded0354412ae | 380 | step_num_l++; |
eri | 0:c1476d342c13 | 381 | } |
eri | 0:c1476d342c13 | 382 | |
eri | 0:c1476d342c13 | 383 | |
kageyuta | 1:86c4c38abe40 | 384 | void setup() |
kageyuta | 1:86c4c38abe40 | 385 | { |
eri | 0:c1476d342c13 | 386 | can1.frequency(1000000); |
eri | 0:c1476d342c13 | 387 | motor_lo_f.period_us(100); |
eri | 0:c1476d342c13 | 388 | motor_lo_b.period_us(100); |
eri | 0:c1476d342c13 | 389 | motor_li_f.period_us(100); |
eri | 0:c1476d342c13 | 390 | motor_li_b.period_us(100); |
kageyuta | 1:86c4c38abe40 | 391 | |
eri | 0:c1476d342c13 | 392 | hand.mode(PullUp); |
kageyuta | 2:55c616d2e0fe | 393 | switch_lo.mode(PullUp); |
kageyuta | 2:55c616d2e0fe | 394 | switch_li.mode(PullUp); |
eri | 0:c1476d342c13 | 395 | switch4.mode(PullUp); |
kageyuta | 1:86c4c38abe40 | 396 | |
eri | 0:c1476d342c13 | 397 | |
eri | 0:c1476d342c13 | 398 | device.baud(115200); |
eri | 0:c1476d342c13 | 399 | device.format(8,Serial::None,1); |
eri | 0:c1476d342c13 | 400 | device.attach(dev_rx, Serial::RxIrq); |
eri | 0:c1476d342c13 | 401 | wait(0.05); |
eri | 0:c1476d342c13 | 402 | theta0=degree0; |
eri | 0:c1476d342c13 | 403 | check_gyro(); |
eri | 0:c1476d342c13 | 404 | } |
eri | 0:c1476d342c13 | 405 | |
eri | 0:c1476d342c13 | 406 | |
eri | 0:c1476d342c13 | 407 | //////////////////////////////////////can |
yuto17320508 | 4:81f01f93e502 | 408 | void can_send(float target_ro, float target_ri) |
eri | 0:c1476d342c13 | 409 | { |
kageyuta | 1:86c4c38abe40 | 410 | char data[4]= {0}; |
eri | 0:c1476d342c13 | 411 | int target_ro_send=target_ro+360; |
eri | 0:c1476d342c13 | 412 | int target_ri_send=target_ri+360; |
eri | 0:c1476d342c13 | 413 | data[0]=target_ro_send & 0b11111111; |
eri | 0:c1476d342c13 | 414 | data[1]=target_ri_send & 0b11111111; |
eri | 0:c1476d342c13 | 415 | data[2]=(target_ro_send>>8) | ((target_ri_send>>4) & 0b11110000); |
eri | 0:c1476d342c13 | 416 | data[3]=hand_mode; |
kageyuta | 1:86c4c38abe40 | 417 | |
eri | 0:c1476d342c13 | 418 | if(can1.write(CANMessage(0,data,4)))led4=1; |
eri | 0:c1476d342c13 | 419 | else led4=0; |
kageyuta | 1:86c4c38abe40 | 420 | } |
kageyuta | 2:55c616d2e0fe | 421 | void reset() |
kageyuta | 2:55c616d2e0fe | 422 | { |
kageyuta | 2:55c616d2e0fe | 423 | while(switch_lo.read()) { |
kageyuta | 6:fe9fa8c2e6f9 | 424 | motor_lo.output(0.3); |
kageyuta | 2:55c616d2e0fe | 425 | } |
yuto17320508 | 5:63462d696256 | 426 | ec_lo.reset(); |
yuto17320508 | 5:63462d696256 | 427 | motor_lo.output(0.0); |
kageyuta | 2:55c616d2e0fe | 428 | while(switch_li.read()) { |
kageyuta | 6:fe9fa8c2e6f9 | 429 | motor_li.output(0.3); |
kageyuta | 2:55c616d2e0fe | 430 | } |
yuto17320508 | 5:63462d696256 | 431 | ec_li.reset(); |
yuto17320508 | 5:63462d696256 | 432 | motor_li.output(0.0); |
kageyuta | 1:86c4c38abe40 | 433 | } |
kageyuta | 1:86c4c38abe40 | 434 |