タコ 駆動側
Dependencies: 2017NHKpin_config FEP R1307 PID ikarashiMDC omni_wheel
Fork of NHK2017_octopus2 by
Revision 1:845af5425eec, committed 2017-09-05
- Comitter:
- uchitake
- Date:
- Tue Sep 05 16:11:20 2017 +0900
- Parent:
- 0:f022e319d359
- Child:
- 2:17015107f466
- Commit message:
- mbed-os5
Changed in this revision
diff -r f022e319d359 -r 845af5425eec 2017NHKpin_config.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/2017NHKpin_config.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://developer.mbed.org/teams/NHK-Robocon2016_Nagaoka_B_Team/code/2017NHKpin_config/#ee450f68d539
diff -r f022e319d359 -r 845af5425eec bot/PIDcontroller/PID_controller.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/PIDcontroller/PID_controller.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,81 @@ +#include "PID_controller.h" + +void PIDC::updateOutput() +{ + confirm(); +} + +PIDC::PIDC() : + PID(KC, TI, TD, INTERVAL), + HMC6352(HMCsda, HMCscl), + rawDegree(0), + offSetDegree(0), + turnOverNumber(0), + beforeDegree(0), + co(0), + processValue(0), + initDegree(0) +{ + PID::setInputLimits(-INPUT_LIMIT, INPUT_LIMIT); + PID::setOutputLimits(-OUTPUT_LIMIT, OUTPUT_LIMIT); + PID::setBias(BIAS); + PID::setMode(AUTO_MODE); + PID::setSetPoint(0.0); + + HMC6352::setOpMode(HMC6352_CONTINUOUS, 1, 20); + rawDegree = HMC6352::sample(); + beforeDegree = HMC6352::sample(); + offSetDegree = HMC6352::sample(); + initDegree = 0; + turnOverNumber = 0; +// this -> attach(this, &PIDC::updateOutput, INTERVAL); +} + +PIDC::PIDC(PinName sda, PinName scl, float kc, float ti, float td, float interval) : + PID(kc, ti, td, interval), + HMC6352(sda, scl), + rawDegree(0), + offSetDegree(0), + turnOverNumber(0), + beforeDegree(0), + co(0), + processValue(0), + initDegree(0) +{ + PID::setInputLimits(-INPUT_LIMIT, INPUT_LIMIT); + PID::setOutputLimits(-OUTPUT_LIMIT, OUTPUT_LIMIT); + PID::setBias(BIAS); + PID::setMode(AUTO_MODE); + PID::setSetPoint(0.0); + + HMC6352::setOpMode(HMC6352_CONTINUOUS, 1, 20); + rawDegree = HMC6352::sample(); + beforeDegree = HMC6352::sample(); + offSetDegree = HMC6352::sample(); + initDegree = 0; + turnOverNumber = 0; +// this -> attach(this, &PIDC::updateOutput, INTERVAL); +} + + +void PIDC::confirm() +{ + rawDegree = HMC6352::sample(); + if(rawDegree - beforeDegree < -1800) turnOverNumber++; + if(rawDegree - beforeDegree > 1800) turnOverNumber--; + initDegree = rawDegree - offSetDegree + turnOverNumber * 3600; + beforeDegree = HMC6352::sample(); + PID::setProcessValue(initDegree / 10.0); + co = PID::compute(); +} + +float PIDC::getCo() const +{ + return co; +} + + +void PIDC::calibration(int mode) +{ + setCalibrationMode(mode); +}
diff -r f022e319d359 -r 845af5425eec bot/PIDcontroller/PID_controller.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/PIDcontroller/PID_controller.h Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,79 @@ +/** +* @file PID_controller.h +* @brief コンパスセンサを使ったPIDコントローラ +* +* Example : +* @code +* #include "mbed.h" +* #include "PID_controller.h" +* +* PIDC pidc; +* +* int main() +* { +* while(1) { +* pidc.confirm(); +* pc.printf("Hi, %f\r\n", pid.getCo()); +* } +* } +* @endcode +*/ +#ifndef PID_CONTROLLER_H +#define PID_CONTROLLER_H + +#include "mbed.h" +#include "pin_config.h" + +#include "PID.h" +#include "HMC6352.h" + +// const double M_PI = 3.141592653589793; +const double KC = 5.0; +const double TI = 0.0; +const double TD = 0.0; +const float INTERVAL = 0.05; +const float INPUT_LIMIT = 180.0; +const float OUTPUT_LIMIT = 0.4; +const float BIAS = 0.0; + +/** +* @brief コンパスセンサを使ったPIDコントローラ +*/ +class PIDC : public PID, HMC6352, Ticker +{ +public : + /** + * @brief defaultコンストラクタ,タイマ割り込みでの計算開始 + */ + PIDC(); + + /** + * @brief コンストラクタ + * @param sda sda HMC6352 + * @param scl scl HMC6352 + * @param kc KC + * @param ti TI + * @param td TD + * @param interval interval + */ + PIDC(PinName sda, PinName scl, float kc, float ti, float td, float interval); + + void confirm(); + float getCo() const; + void calibration(int mode); +private : + + void updateOutput(); + + int rawDegree; + int offSetDegree; + int turnOverNumber; + int beforeDegree; + +protected : + float co; + float processValue; + int initDegree; +}; + +#endif//PID_CONTROLLER_H
diff -r f022e319d359 -r 845af5425eec bot/bot.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/bot.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,68 @@ +#include "bot.h" + +Bot::Bot() : + PIDC(), pad(XBee1TX, XBee1RX, ADDR), motor(MDSDA, MDSCL, solenoidPin) +{ + motor.goXY(0, 0, 0); + motor.moveSlider(0); + motor.destroy(0); + motor.swing(0); + motor.shakeHead(0); +} + +void Bot::confirmAll() +{ + suc = pad.receiveState(); + PIDC::confirm(); + if(pad.getNorm(1) > 0.5) PIDC::setSetPoint(pad.getRadian(1) * (180.0 / M_PI) - M_PI / 2.0); + if(!suc) { + motor.goXY(0, 0, 0); + motor.moveSlider(0); + motor.destroy(0); + motor.swing(0); + motor.shakeHead(0); + } +} + +void Bot::controllDrive() +{ + if(suc) motor.goXY(pad.getStick(0) / 2.0,-pad.getStick(1) / 2.0, PIDC::co); +} + +void Bot::controllMech() +{ + if(suc) { +// if(!pad.getButton1(0)) motor.moveSlider(ARM_MAX_SPEED); +// if(!pad.getButton1(1)) motor.moveSlider(-ARM_MAX_SPEED); +// if(pad.getButton1(0) && pad.getButton1(1)) motor.moveSlider(0); +// +// if(!pad.getButton1(3)) motor.shakeHead(ARM_MAX_SPEED); +// if(!pad.getButton1(4)) motor.shakeHead(-ARM_MAX_SPEED); +// if(pad.getButton1(3) && pad.getButton1(4)) motor.shakeHead(0); +// + if(!pad.getButton1(5)) motor.swing(0.2); + if(!pad.getButton1(6)) motor.swing(-0.2); + if(pad.getButton1(5) && pad.getButton1(6)) motor.swing(0); + +// +// if(!pad.getButton1(2)) { +// motor.destroy(DESTROY_MAX_SPEED); +// } else { +// motor.destroy(0); +// } +// +// if(!pad.getButton2(0)) motor.release(); + } +} + + +void Bot::calibrate() +{ + if(suc && !pad.getButton2(0) && !pad.getButton2(1) && !pad.getButton2(2) && !pad.getButton2(3)) { + PIDC::calibration(HMC6352_ENTER_CALIB); + motor.goXY(0, 0, 0.3); + wait(2.0); + motor.goXY(0, 0, 0); + PIDC::calibration(HMC6352_EXIT_CALIB); + } +} \ No newline at end of file
diff -r f022e319d359 -r 845af5425eec bot/bot.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/bot.h Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,51 @@ +/** +* @file bot.h +* @brief ロボットのクラス +*/ +#ifndef BOT_H +#define BOT_H + +#include "mbed.h" +#include "pin_config.h" +#include "motor_driver.h" +#include "controller.h" +#include "PID_controller.h" + +#define ARM_MAX_SPEED 1 +#define DESTROY_MAX_SPEED 1 + +/** +* @brief ロボットのクラス +*/ +class Bot : public PIDC +{ +public : + /** + * @brief コンストラクタ + */ + Bot(); + + /** + * @brief センサなどの値を更新 + */ + void confirmAll(); + + /** + * @brief 足回りの制御 + */ + void controllDrive(); + + /** + * @brief 機構部の制御 + */ + void controllMech(); + + void calibrate(); + +private : + Controller pad; + MotorDriver motor; + bool suc; +}; + +#endif//BOT_H
diff -r f022e319d359 -r 845af5425eec bot/controller/controller.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/controller/controller.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,92 @@ +#include "controller.h" + +Controller::Controller() : + FEP(XBee1TX, XBee1RX, ADDR), + data(), + fepTemp(0), + button1(), + button2(), + stick(), + radian(), + norm() +{ +} + +Controller::Controller(PinName FEPtx, PinName FEPrx, int addr) : + FEP(FEPtx, FEPrx, addr), + data(), + fepTemp(0), + button1(), + button2(), + stick(), + radian(), + norm() +{ +} + +bool Controller::receiveState() +{ + fepTemp = FEP::read(data, DATA_SIZE); + if(fepTemp == FEP_SUCCESS) { + for(int i = 0; i < 7; i++) { + button1[i] = data[4] % 2; + data[4] /= 2; + } + for(int i=0; i<6; i++) { + button2[i] = data[5] % 2; + data[5] /= 2; + } + for(int i = 0; i < 4; i++) { + stick[i] = -((double)(data[i] / STICK_DIVIDE) * 2.0 - 1.0); + } + setStick(); + } else if(fepTemp == FEP_NO_RESPONSE) { + return 0; + } else { + return 0; + } + return 1; +} + +void Controller::setStick() +{ + for(int i = 0; i < 4; i++) { + if(stick[i] < STICK_NEWTRAL && stick[i] > -STICK_NEWTRAL) stick[i] = 0; + } + + radian[0] = atan2(stick[1], -stick[0]); + radian[1] = atan2(stick[3], -stick[2]); + + norm[0] = hypot(stick[0], stick[1]); + norm[1] = hypot(stick[2], stick[3]); + + if(norm[0] < STICK_NEWTRAL) norm[0] = 0; + if(norm[1] < STICK_NEWTRAL) norm[1] = 0; + if(norm[0] > STICK_NORM_MAX) norm[0] = STICK_NORM_MAX; + if(norm[1] > STICK_NORM_MAX) norm[1] = STICK_NORM_MAX; +} + +bool Controller::getButton1(int number) const +{ + return button1[number]; +} + +bool Controller::getButton2(int number) const +{ + return button2[number]; +} + +float Controller::getStick(int number) const +{ + return stick[number]; +} + +float Controller::getRadian(int number) const +{ + return radian[number]; +} + +float Controller::getNorm(int number) const +{ + return norm[number]; +}
diff -r f022e319d359 -r 845af5425eec bot/controller/controller.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/controller/controller.h Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,118 @@ +/** +* @file controller.h +* @brief FEPを使ったコントローラ受信部 +* +* Example : +* @code +* #include "mbed.h" +* #include "controller.h" +* +* Controller pad(PA_9, PA_10, 200); +* Serial pc(USBTX, USBRX, 115200); +* +* int main() +* { +* while(1) { +* if(pad.receiveState()) { +* for(int i = 0; i < 7; i++) pc.printf("%d, ", pad.getButton1(i)); +* for(int i = 0; i < 6; i++) pc.printf("%d, ", pad.getButton2(i)); +* pc.printf("\r\n"); +* } else { +* pc.printf("ERROR\n\r"); +* } +* } +* } +* @endcode +*/ +#ifndef CONTROLLER_H +#define CONTROLLER_H + +#include "mbed.h" +#include "pin_config.h" +#include <math.h> + +#include "FEP.h" + +// const double M_PI = 3.141592653589793; +const int ADDR = 203; +const bool FEP_SUCCESS =0; +const int DATA_SIZE = 6; +const float STICK_DIVIDE = 255.0; +const float STICK_NEWTRAL = 0.1; +const float STICK_NORM_MAX =1.0; + +/** +* @brief FEPを使ったコントローラのクラス +*/ +class Controller : public FEP +{ +public : + + /** + * @brief コンストラクタ + */ + Controller(); + + /** + * @brief コンストラクタ + * @param FEPtx FEPtx + * @param FEPrx FEPrx + * @param addr address + */ + Controller(PinName FEPtx, PinName FEPrx,int addr); + + /** + * @brief メンバ変数にボタンのステートを格納 + */ + bool receiveState(); + + /** + * ボタン1の状態を取得 + * @param number button number + * @return status + */ + bool getButton1(int number) const; + + /** + * ボタン2の状態を取得 + * @param number button number + * @return status + */ + bool getButton2(int number) const; + + /** + * スティックの値を取得 + * @param number sticknumber(x, y, x, y) + * @return stick value + */ + float getStick(int number) const; + + /** + * スチィックの角度を取得 + * @param number left...0 right...1 + * @return radian + */ + float getRadian(int number) const; + + /** + * スティックの距離を取得 + * @param number left..0 right..1 + * @return norm + */ + float getNorm(int number) const; + +private : + void setStick(); + + char data[6]; + uint8_t fepTemp; + +protected : + bool button1[7]; + bool button2[6]; + double stick[4]; + double radian[2]; + double norm[2]; +}; + +#endif//CONTROLLER_H
diff -r f022e319d359 -r 845af5425eec bot/motor_driver/arm_unit/arm_unit.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/motor_driver/arm_unit/arm_unit.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,32 @@ +#include "arm_unit.h" + +void Arm::resetHeight(void) +{ + QEI::reset(); + heightResetFlag = 1; +} + +Arm::Arm() : + QEI(Sensor4pin1a, Sensor4pin1b, NC, PULSES_PER_REV, X2_ENCODING), + limitSwitch(Sensor3pin3a), + heightResetFlag(0) +{ + QEI::reset(); + // limitSwitch.rise(this, &Arm::resetHeight); + limitSwitch.rise(callback(this, &Arm::resetHeight)); +} + +bool Arm::isPushed() +{ + return limitSwitch.read(); +} + +bool Arm::isResetted() const +{ + return heightResetFlag; +} + +int Arm::getHeight() +{ + return QEI::getCurrentState(); +}
diff -r f022e319d359 -r 845af5425eec bot/motor_driver/arm_unit/arm_unit.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/motor_driver/arm_unit/arm_unit.h Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,54 @@ +/** +* @file arm_unit.h +* @brief アーム機構のStateクラス +*/ +#ifndef ARM_UNIT_H +#define ARM_UNIT_H + +#include "mbed.h" +#include "pin_config.h" + +#include "QEI.h" + +const int PULSES_PER_REV = 6; +// #define SLIDER_POINT + +/** +* @brief アーム機構のStateクラス +*/ +class Arm : public QEI { +public : + + /** + * @brief コンストラクタ + */ + Arm(); + + /** + * @bref スライダ高さリセット用のリミットスイッチの状態 + * @return limitSwitch + */ + bool isPushed(); + + /** + * @brief 高さの値がリセットされたことがあるか + * @return heightResetFlag(bool) + */ + bool isResetted() const; + + /** + * @brief 高さを取得 + * @return height + */ + int getHeight(); + +private : + void resetHeight(); + InterruptIn limitSwitch; + +protected : + bool heightResetFlag; + +}; + +#endif//ARM_UNIT_H
diff -r f022e319d359 -r 845af5425eec bot/motor_driver/motor_driver.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/motor_driver/motor_driver.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,74 @@ +#include "motor_driver.h" + +MotorDriver::MotorDriver() : + MDC(MDSDA, MDSCL), + quadOmni(WHEEL_NUMBER), + solenoid(solenoidPin) +{ + MDC::MotorSTOP(); + quadOmni.setWheelRadian( + WHEEL_RADIAN / 2.0, + WHEEL_RADIAN /2.0 + WHEEL_RADIAN, + -WHEEL_RADIAN / 2.0, + -WHEEL_RADIAN /2.0 - WHEEL_RADIAN + ); + solenoid = 0; +} + +MotorDriver::MotorDriver(PinName sda, PinName scl, PinName solPin) : + MDC(sda, scl), + quadOmni(WHEEL_NUMBER), + solenoid(solPin) +{ + MDC::MotorSTOP(); + quadOmni.setWheelRadian( + WHEEL_RADIAN / 2.0, + WHEEL_RADIAN /2.0 + WHEEL_RADIAN, + -WHEEL_RADIAN / 2.0, + -WHEEL_RADIAN /2.0 - WHEEL_RADIAN + ); + solenoid = 0; +} + +void MotorDriver::moveSlider(float speed) +{ + if(!arm.isResetted() && speed < 0) speed = 0; + if(arm.isPushed() && speed > 0) speed = 0; + MDC::write(ARM_MDC_ADDR, SLIDER_NUMBER, speed); +} + +void MotorDriver::swing(float speed) +{ + MDC::write(ARM_MDC_ADDR, SWORD_NUMBER, speed); +} + +void MotorDriver::shakeHead(float speed) +{ + MDC::write(ARM_MDC_ADDR, SHAKE_NUMBER, speed); +} + +void MotorDriver::release() +{ + solenoid = 1; +} + +void MotorDriver::destroy(float speed) +{ + write(ARM_MDC_ADDR, ARM_NUMBER, speed); +} + +void MotorDriver::goXY(float X, float Y, float moment) +{ + quadOmni.computeXY(X, Y, moment); + for(int i = 0; i < 4; i++) { + write(WHEEL_MDC_ADDR, i, quadOmni.getOutput(i)); + } +} + +void MotorDriver::goCircular(float r, float rad, float moment) +{ + quadOmni.computeCircular(r, rad, moment); + for(int i = 0; i < 4; i++) { + write(WHEEL_MDC_ADDR, i, quadOmni.getOutput(i)); + } +}
diff -r f022e319d359 -r 845af5425eec bot/motor_driver/motor_driver.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/bot/motor_driver/motor_driver.h Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,98 @@ +/** +* @file motor_driver.h +* @brief モータ駆動クラス +* +* Example : +* @code +* #include "mbed.h" +* #include "motor_driver.h" +* +* MotorDriver(PB_9, PB_8, PA_5); +* Serial pc(USBTX, USBRX, 115200); +* +* int main() +* { +* while(1) { +* motor.goXY(0.1, 0.1, 0); +* } +* } +* @endcode +*/ +#ifndef MOTOR_DRIVER_H +#define MOTOR_DRIVER_H + +#include "mbed.h" +#include "pin_config.h" + +#include "arm_unit.h" +#include "omni.h" +#include "MotorDriverController.h" + +const int WHEEL_NUMBER = 4; +const float WHEEL_RADIAN = M_PI / 2.0; +const int WHEEL_MDC_ADDR = 7; +const int ARM_MDC_ADDR = 6; +const int SLIDER_NUMBER = 0; +const int ARM_NUMBER = 1; +const int SWORD_NUMBER = 2; +const int SHAKE_NUMBER = 3; + +/** +* @brief モータ駆動クラス +*/ +class MotorDriver : MDC { +public : + /** + * @brief コンストラクタ + */ + MotorDriver(); + + MotorDriver(PinName sda, PinName scl, PinName solPin); + + /** + * @brief スライダを動かす + */ + void moveSlider(float speed); + + /** + * @brief ひみつ道具部分を動かす + */ + void destroy(float speed); + + /** + * @brief 剣を振る + * @param speed 速度 + */ + void swing(float speed); + + /** + * @brief ひみつ道具の首振り + * @param speed 速度 + */ + void shakeHead(float speed); + + /** + * @brief 解放機構 + */ + void release(); + + /** + * @brief あしまわりを動かす(X, Y) + */ + void goXY(float X, float Y, float moment); + + /** + * @brief 足回りを動かす(circular) + * @param r 半径 + * @param rad 角度 + * @param moment 回転 + */ + void goCircular(float r, float rad, float moment); + +private : + Arm arm; + Omni quadOmni; + DigitalOut solenoid; +}; + +#endif//MOTOR_DRIVER_H
diff -r f022e319d359 -r 845af5425eec classDiagram.pu --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/classDiagram.pu Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,107 @@ +@startuml + +class Bot { + +Bot() + +confirmAll() + +controllDrive() + +controllMech() + +calibrate() + + ~pad + ~motor + -suc +} + +class Controller { + +Controller() + +receiveState() + +getButton1() + +getButton2() + +getStick() + +getRadian() + +getNorm() + + -setStick() + -data[6] + -fepTemp + + #button1[7] + #button2[6] + #stick[4] + #radian[2] + #norm[2] +} + +class MotorDriver { + +MotorDriver() + +moveSlider() + +destroy() + +swing() + +shakeHead() + +release() + +goXY() + +goCircular() + + ~arm + ~quadOmni + ~solenoid +} + +class PIDC { + +PIDC() + +confirm() + +getCo() + +calibration() + + -updateOutput() + -rawDegree + -offSetDegree + -turnOverNumber + -beforeDegree + + #co + #processValue + #initDegree +} + +class Arm { + +Arm() + +isPushed() + +isResetted() + +getHeight() + + -resetHeight() + ~ limitSwitch + + #heightResetFlag +} + +class WheelUnit { + +WheelUnit() +} + +object pin_config +object FEP +object HMC6352 +object MDC +object Omni +object PID +object QEI + +Bot o.. Controller +Bot o.. MotorDriver +Bot o.. PIDC + +MotorDriver <-. Arm +MotorDriver <-. WheelUnit + +Bot .right. pin_config + +Controller . FEP +MotorDriver . MDC +WheelUnit . Omni +PIDC .. PID +PIDC .. HMC6352 +Arm . QEI + +@enduml
diff -r f022e319d359 -r 845af5425eec libs/FEP.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/FEP.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://mbed.org/teams/NHK-Robocon2016_Nagaoka_B_Team/code/FEP/#74e21751ac10
diff -r f022e319d359 -r 845af5425eec libs/HMC6352.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/HMC6352.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://mbed.org/users/aberk/code/HMC6352/#83c0cb554099
diff -r f022e319d359 -r 845af5425eec libs/MotorDriverController.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/MotorDriverController.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://developer.mbed.org/teams/NHK-Robocon2016_Nagaoka_B_Team/code/MotorDriverController/#caf0cea235b2
diff -r f022e319d359 -r 845af5425eec libs/PID.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/PID.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://mbed.org/users/aberk/code/PID/#6e12a3e5af19
diff -r f022e319d359 -r 845af5425eec libs/QEI.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/QEI.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://mbed.org/users/aberk/code/QEI/#5c2ad81551aa
diff -r f022e319d359 -r 845af5425eec libs/omni.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/libs/omni.lib Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,1 @@ +https://developer.mbed.org/teams/NHK-Robocon2016_Nagaoka_B_Team/code/omni/#4f0b55344c73
diff -r f022e319d359 -r 845af5425eec main.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,19 @@ +#include "mbed.h" +#include "pin_config.h" +#include "bot.h" + +Bot KANI; +Serial pc(USBTX, USBRX, 115200); + +int main() +{ + int i = 0; + pc.printf("const\n\r"); + while(1) { + KANI.confirmAll(); + KANI.controllDrive(); + KANI.controllMech(); + wait(INTERVAL); + pc.printf("%d\n\r", i++); + } +}
diff -r f022e319d359 -r 845af5425eec use_case.pu --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/use_case.pu Tue Sep 05 16:11:20 2017 +0900 @@ -0,0 +1,15 @@ +@startuml + +actor user + +user -> (controller) : controll +controller --> (MCU) : FEP_serial +MCU --> (MDC) : I2C +MCU --> (solenoid) : DigitalOut +MCU <-- (HMC6352) : I2C (via PIDControler) +MCU <-- (QEI) : DigitalIn +MCU <-- (limitSwitch) : DigitalIn +MDC --> (quadOmni) +MDC --> (gimmicks) + +@enduml