use for experiment before the demonstration at open-campus
Dependencies: FEP ikarashiMDC omni PID R1370
Fork of omni_sample by
main.cpp@10:73148221684e, 2017-09-04 (annotated)
- Committer:
- tknara
- Date:
- Mon Sep 04 02:59:46 2017 +0000
- Revision:
- 10:73148221684e
- Parent:
- 9:8f9607783d2d
- Child:
- 11:a2e3d11f5750
Ha?
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
UCHITAKE | 0:6c83a0871cc3 | 1 | #include "mbed.h" |
UCHITAKE | 0:6c83a0871cc3 | 2 | #include "omni.h" |
tknara | 7:ef72ec7390c2 | 3 | #include "ikarashiMDC.h" |
UCHITAKE | 0:6c83a0871cc3 | 4 | #include "pin_config.h" |
eil4nyqn | 1:ba8cdae2652a | 5 | #include "FEP.h" |
tknara | 9:8f9607783d2d | 6 | #include "controller.h" |
tknara | 10:73148221684e | 7 | #include "PID.h" |
tknara | 10:73148221684e | 8 | #include "R1370.h" |
UCHITAKE | 0:6c83a0871cc3 | 9 | |
tknara | 5:dee9310ec990 | 10 | #define DEBUG |
tknara | 10:73148221684e | 11 | |
tknara | 10:73148221684e | 12 | #define KP 5 |
tknara | 10:73148221684e | 13 | #define KI 0 |
tknara | 10:73148221684e | 14 | #define KD 0 |
tknara | 10:73148221684e | 15 | #define RATE 0.01 |
tknara | 7:ef72ec7390c2 | 16 | Omni omni(4); |
tknara | 9:8f9607783d2d | 17 | Serial RS485(RS485_TX,RS485_RX,38400); |
tknara | 9:8f9607783d2d | 18 | Serial pc(USBTX,USBRX,115200); |
tknara | 9:8f9607783d2d | 19 | Controller con(FEP_TX,FEP_RX,200); |
tknara | 10:73148221684e | 20 | DigitalOut RS485control(PA_4); |
tknara | 10:73148221684e | 21 | //DigitalOut leds[4] = {PC_13,PC_14,PC_15,PA_0}; |
tknara | 5:dee9310ec990 | 22 | DigitalOut attack[2] = {PA_10,PC_4}; |
tknara | 5:dee9310ec990 | 23 | DigitalOut angle[2] = {PB_3,PB_5}; |
tknara | 10:73148221684e | 24 | R1370 R1370(R1370_TX,R1370_RX); |
tknara | 10:73148221684e | 25 | PID pid(KP,KI,KD,RATE); |
tknara | 7:ef72ec7390c2 | 26 | ikarashiMDC wheels[] { |
tknara | 8:244c057d195c | 27 | ikarashiMDC(&RS485control,0,0,SM,&RS485), |
tknara | 8:244c057d195c | 28 | ikarashiMDC(&RS485control,1,3,SM,&RS485), |
tknara | 8:244c057d195c | 29 | ikarashiMDC(&RS485control,1,0,SM,&RS485), |
tknara | 8:244c057d195c | 30 | ikarashiMDC(&RS485control,0,3,SM,&RS485) |
tknara | 7:ef72ec7390c2 | 31 | }; |
tknara | 7:ef72ec7390c2 | 32 | ikarashiMDC lift[] { |
tknara | 9:8f9607783d2d | 33 | ikarashiMDC(&RS485control,1,1,SM,&RS485) |
tknara | 7:ef72ec7390c2 | 34 | }; |
WAT34 | 3:4cd170cdf049 | 35 | void init() |
WAT34 | 3:4cd170cdf049 | 36 | { |
tknara | 10:73148221684e | 37 | pc.printf("Hello\n"); |
tknara | 8:244c057d195c | 38 | int i; |
tknara | 8:244c057d195c | 39 | for(i = 0;i < 4;i++) { |
tknara | 8:244c057d195c | 40 | wheels[i].braking = true; |
tknara | 8:244c057d195c | 41 | } |
tknara | 9:8f9607783d2d | 42 | lift[0].braking = true; |
tknara | 7:ef72ec7390c2 | 43 | omni.setWheelRadian(PI/4,3*PI/4,5*PI/4,7*PI/4); |
tknara | 8:244c057d195c | 44 | for(i = 0;i<4;i++) { |
tknara | 10:73148221684e | 45 | //leds[i] = 0; |
WAT34 | 3:4cd170cdf049 | 46 | } |
WAT34 | 3:4cd170cdf049 | 47 | } |
tknara | 10:73148221684e | 48 | void pidInit() |
tknara | 10:73148221684e | 49 | { |
tknara | 10:73148221684e | 50 | pid.reset(); |
tknara | 10:73148221684e | 51 | pid.setInputLimits(-180.0,180.0); |
tknara | 10:73148221684e | 52 | pid.setOutputLimits(-1.0,1.0); |
tknara | 10:73148221684e | 53 | pid.setMode(1); |
tknara | 10:73148221684e | 54 | pid.setSetPoint(0.0); |
tknara | 10:73148221684e | 55 | pid.setBias(0.0); |
tknara | 10:73148221684e | 56 | } |
tknara | 5:dee9310ec990 | 57 | void AllActuatorStop() |
tknara | 5:dee9310ec990 | 58 | { |
tknara | 5:dee9310ec990 | 59 | #ifdef DEBUG |
tknara | 7:ef72ec7390c2 | 60 | pc.printf("All actuators stop\n"); |
tknara | 5:dee9310ec990 | 61 | #endif |
tknara | 6:259deb365510 | 62 | for(int i=0;i<1;i++) |
tknara | 6:259deb365510 | 63 | { |
tknara | 6:259deb365510 | 64 | attack[i]=0; |
tknara | 6:259deb365510 | 65 | angle[i]=0; |
tknara | 6:259deb365510 | 66 | } |
tknara | 5:dee9310ec990 | 67 | } |
UCHITAKE | 0:6c83a0871cc3 | 68 | int main() |
tknara | 6:259deb365510 | 69 | { |
tknara | 6:259deb365510 | 70 | bool airFlag1=0,airFlag2=0,airStatus1=0,airStatus2=0; |
tknara | 9:8f9607783d2d | 71 | int error_val = 0; |
eil4nyqn | 1:ba8cdae2652a | 72 | uint8_t fep_temp; |
tknara | 5:dee9310ec990 | 73 | double pwm = 0.0; |
tknara | 8:244c057d195c | 74 | init(); |
tknara | 10:73148221684e | 75 | pidInit(); |
tknara | 10:73148221684e | 76 | while(1) |
tknara | 10:73148221684e | 77 | { |
tknara | 10:73148221684e | 78 | if(con.receiveState()==0) |
tknara | 10:73148221684e | 79 | { |
eil4nyqn | 1:ba8cdae2652a | 80 | error_val = 0; |
tknara | 10:73148221684e | 81 | //leds[0] = 0; |
tknara | 10:73148221684e | 82 | if((R1370.reciveState() == 0)&&(error_val < 4)) |
tknara | 10:73148221684e | 83 | { |
tknara | 10:73148221684e | 84 | //omni.computeXY(-1*con.getStick(2),con.getStick(3),con.getStick(0)/-2.0); |
tknara | 10:73148221684e | 85 | pid.setProcessValue(R1370.getAngle()); |
tknara | 10:73148221684e | 86 | pc.printf("%lf %lf ",R1370.getAngle(),-1*pid.compute()); |
tknara | 10:73148221684e | 87 | omni.computeXY(-1*con.getStick(2),con.getStick(3),-1*pid.compute()); |
tknara | 10:73148221684e | 88 | for(int i = 0; i < 4; i++) { |
tknara | 10:73148221684e | 89 | pc.printf("%lf,",omni.getOutput(i)); |
tknara | 10:73148221684e | 90 | wheels[i].setSpeed(omni.getOutput(i)); |
tknara | 10:73148221684e | 91 | } |
tknara | 10:73148221684e | 92 | pc.printf("\n"); |
UCHITAKE | 0:6c83a0871cc3 | 93 | } |
tknara | 5:dee9310ec990 | 94 | //昇降 |
tknara | 9:8f9607783d2d | 95 | if(con.getButton1(0) == 1 && con.getButton1(1) == 0) { |
tknara | 9:8f9607783d2d | 96 | pwm = -0.9; |
tknara | 9:8f9607783d2d | 97 | } else if(con.getButton1(0) == 0 && con.getButton1(1) == 1) { |
tknara | 5:dee9310ec990 | 98 | pwm = 0.9; |
eil4nyqn | 1:ba8cdae2652a | 99 | } else { |
tknara | 8:244c057d195c | 100 | pwm = 0.0; |
eil4nyqn | 1:ba8cdae2652a | 101 | } |
tknara | 7:ef72ec7390c2 | 102 | lift[0].setSpeed(pwm); |
tknara | 6:259deb365510 | 103 | //アーム攻撃(toggle) |
tknara | 9:8f9607783d2d | 104 | if((con.getButton2(1)==0)&&(airFlag1 == 0)) |
tknara | 5:dee9310ec990 | 105 | { |
tknara | 6:259deb365510 | 106 | if(airStatus1==1) { |
tknara | 6:259deb365510 | 107 | attack[0]=0; |
tknara | 6:259deb365510 | 108 | attack[1]=1; |
tknara | 6:259deb365510 | 109 | airFlag1=1; |
tknara | 6:259deb365510 | 110 | airStatus1=0; |
tknara | 6:259deb365510 | 111 | }else if(airStatus1==0) { |
tknara | 6:259deb365510 | 112 | attack[0]=1; |
tknara | 6:259deb365510 | 113 | attack[1]=0; |
tknara | 6:259deb365510 | 114 | airFlag1=1; |
tknara | 6:259deb365510 | 115 | airStatus1=1; |
tknara | 6:259deb365510 | 116 | } |
tknara | 9:8f9607783d2d | 117 | }else if(con.getButton2(1)==1){ |
tknara | 6:259deb365510 | 118 | airFlag1=0; |
tknara | 5:dee9310ec990 | 119 | attack[0]=0; |
tknara | 5:dee9310ec990 | 120 | attack[1]=0; |
tknara | 5:dee9310ec990 | 121 | } |
tknara | 6:259deb365510 | 122 | //アーム角度(toggle) |
tknara | 9:8f9607783d2d | 123 | if((con.getButton2(3)==0)&&(airFlag2 == 0)) |
tknara | 5:dee9310ec990 | 124 | { |
tknara | 6:259deb365510 | 125 | if(airStatus2==1) { |
tknara | 6:259deb365510 | 126 | angle[0]=0; |
tknara | 6:259deb365510 | 127 | angle[1]=1; |
tknara | 6:259deb365510 | 128 | airFlag2=1; |
tknara | 6:259deb365510 | 129 | airStatus2=0; |
tknara | 6:259deb365510 | 130 | }else if(airStatus2==0) { |
tknara | 6:259deb365510 | 131 | angle[0]=1; |
tknara | 6:259deb365510 | 132 | angle[1]=0; |
tknara | 6:259deb365510 | 133 | airFlag2=1; |
tknara | 6:259deb365510 | 134 | airStatus2=1; |
tknara | 6:259deb365510 | 135 | } |
tknara | 9:8f9607783d2d | 136 | }else if(con.getButton2(3)==1){ |
tknara | 6:259deb365510 | 137 | airFlag2=0; |
tknara | 5:dee9310ec990 | 138 | angle[0]=0; |
tknara | 5:dee9310ec990 | 139 | angle[1]=0; |
tknara | 5:dee9310ec990 | 140 | } |
UCHITAKE | 0:6c83a0871cc3 | 141 | } |
UCHITAKE | 0:6c83a0871cc3 | 142 | } |
UCHITAKE | 0:6c83a0871cc3 | 143 | } |