足回り動かすためのライブラリ
使用例
#include "scrp_slave.hpp" #include "core.hpp" #include "mbed.h" ScrpSlave sendpwm(PC_12,PD_2 ,PH_1 ,SERIAL_TX,SERIAL_RX,0x0807f800); Robot AKASHIKOSEN(50.8,25.4,322.5,259.75); Core RBT(&AKASHIKOSEN,OMNI4,0.02); int main(){ /*--------------SETUP--------------*/ AKASHIKOSEN.setCWID(0,1,2,3); AKASHIKOSEN.setSWID(4,5,6,7); RBT.addENC(PC_4,PA_13,512,4,0); RBT.addENC(PA_14,PA_15,512,4,1); RBT.addENC(PC_2,PC_3,512,4,2); RBT.addENC(PC_10,PC_11,512,4,3); RBT.addENC(PA_7,PA_6,512,4,4); RBT.addENC(PA_9,PA_8,512,4,5); RBT.addENC(PC_1,PC_0,512,4,6); RBT.addENC(PC_5,PA_12,512,4,7); RBT.START(); /*--------------LOOP--------------*/ Position pos; while(true){ pos = RBT.getStatus(); printf("x:%lf,y:%lf,theta:%lf\n",pos.x,pos.y,pos.theta); RBT.LOOP(); } }
core.cpp@11:80800fd9f4af, 2021-10-29 (annotated)
- Committer:
- hamohamo
- Date:
- Fri Oct 29 09:20:31 2021 +0000
- Revision:
- 11:80800fd9f4af
- Parent:
- 10:f434b6848059
asd
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
hamohamo | 0:0a9ce35078a3 | 1 | #include "core.hpp" |
hamohamo | 0:0a9ce35078a3 | 2 | |
hamohamo | 11:80800fd9f4af | 3 | Core::Core(Robot* robot,int mode,double dt):rbt(robot),mode(mode),dt(dt),Mots(5),Encs(9),PIDs(6),IMCs(6){ |
hamohamo | 9:489046c1e624 | 4 | pos.x = 0.0; |
hamohamo | 9:489046c1e624 | 5 | pos.y = 0.0; |
hamohamo | 9:489046c1e624 | 6 | pos.theta = 0.0; |
hamohamo | 9:489046c1e624 | 7 | vel.x = 0.0; |
hamohamo | 9:489046c1e624 | 8 | vel.y = 0.0; |
hamohamo | 9:489046c1e624 | 9 | vel.theta = 0.0;} |
hamohamo | 2:d88ff6dda390 | 10 | Motor* Core::addMOT(PinName plus,PinName minus,int period,int id){ |
hamohamo | 2:d88ff6dda390 | 11 | Mots.at(id) = new Motor(plus,minus,period,id); |
hamohamo | 2:d88ff6dda390 | 12 | return Mots.at(id); |
hamohamo | 2:d88ff6dda390 | 13 | } |
hamohamo | 0:0a9ce35078a3 | 14 | void Core::addENC(PinName plus,PinName minus,int resolution,int mode,int id){Encs.at(id) = new Encoder(plus,minus,resolution,mode,id);} |
hamohamo | 2:d88ff6dda390 | 15 | PID* Core::addPID(double Kp,double Ki,double Kd,int id){ |
hamohamo | 2:d88ff6dda390 | 16 | PIDs.at(id) = new PID(Kp,Ki,Kd,id); |
hamohamo | 2:d88ff6dda390 | 17 | return PIDs.at(id); |
hamohamo | 0:0a9ce35078a3 | 18 | } |
hamohamo | 10:f434b6848059 | 19 | IMC* Core::addIMC(double K,double T,int id){ |
hamohamo | 11:80800fd9f4af | 20 | printf("%d\n",id); |
hamohamo | 10:f434b6848059 | 21 | IMCs.at(id) = new IMC(K,T,id); |
hamohamo | 10:f434b6848059 | 22 | return IMCs.at(id); |
hamohamo | 10:f434b6848059 | 23 | } |
hamohamo | 2:d88ff6dda390 | 24 | void Core::setPWM(double pwm,int id){Mots[id]->setPWM(pwm);} |
hamohamo | 2:d88ff6dda390 | 25 | |
hamohamo | 0:0a9ce35078a3 | 26 | void Core::START(){timer.start();} |
hamohamo | 0:0a9ce35078a3 | 27 | bool Core::LOOP(){ |
hamohamo | 0:0a9ce35078a3 | 28 | bool ret = true; |
hamohamo | 0:0a9ce35078a3 | 29 | long long int temp; |
hamohamo | 0:0a9ce35078a3 | 30 | while(temp <= dt*1000.0*1000.0){ |
hamohamo | 0:0a9ce35078a3 | 31 | temp = timer.read_us()-t; |
hamohamo | 0:0a9ce35078a3 | 32 | if(temp < 0.0){ |
hamohamo | 0:0a9ce35078a3 | 33 | ret = false; |
hamohamo | 0:0a9ce35078a3 | 34 | printf("WARN!:Out of cycle:%lld(us)\n",temp); |
hamohamo | 0:0a9ce35078a3 | 35 | } |
hamohamo | 0:0a9ce35078a3 | 36 | } |
hamohamo | 0:0a9ce35078a3 | 37 | t = timer.read_us(); |
hamohamo | 0:0a9ce35078a3 | 38 | return ret; |
hamohamo | 0:0a9ce35078a3 | 39 | } |
hamohamo | 0:0a9ce35078a3 | 40 | void Core::WAIT(double wt){while(timer.read_us()-t <= wt*1000.0*1000.0);} |
hamohamo | 2:d88ff6dda390 | 41 | void Core::setPosition(double x,double y,double theta){ |
hamohamo | 2:d88ff6dda390 | 42 | pos.x = x; |
hamohamo | 2:d88ff6dda390 | 43 | pos.y = y; |
hamohamo | 2:d88ff6dda390 | 44 | pos.theta = theta; |
hamohamo | 2:d88ff6dda390 | 45 | } |
hamohamo | 0:0a9ce35078a3 | 46 | void Core::setVelocity(double Vx,double Vy,double Vw){ |
hamohamo | 0:0a9ce35078a3 | 47 | double w1,w2,w3,w4; |
hamohamo | 7:c0b6afbccd97 | 48 | double vx,vy; |
hamohamo | 7:c0b6afbccd97 | 49 | vx = cos(pos.theta-M_PI/4.0)*Vx + sin(pos.theta-M_PI/4.0)*Vy; |
hamohamo | 7:c0b6afbccd97 | 50 | vy = - sin(pos.theta-M_PI/4.0)*Vx + cos(pos.theta-M_PI/4.0)*Vy; |
hamohamo | 0:0a9ce35078a3 | 51 | switch(mode){ |
hamohamo | 0:0a9ce35078a3 | 52 | case OMNI4: |
hamohamo | 7:c0b6afbccd97 | 53 | w1 = -vx + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 54 | w2 = vy + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 55 | w3 = vx + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 56 | w4 = -vy + rbt->C2CD*Vw; |
hamohamo | 0:0a9ce35078a3 | 57 | break; |
hamohamo | 0:0a9ce35078a3 | 58 | case OMNI3: |
hamohamo | 0:0a9ce35078a3 | 59 | w1 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 60 | w2 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 61 | w3 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 62 | w4 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 63 | break; |
hamohamo | 0:0a9ce35078a3 | 64 | case MECANUM: |
hamohamo | 0:0a9ce35078a3 | 65 | w1 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 66 | w2 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 67 | w3 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 68 | w4 = 0.0; |
hamohamo | 0:0a9ce35078a3 | 69 | break; |
hamohamo | 8:475c17b23944 | 70 | }/* |
hamohamo | 0:0a9ce35078a3 | 71 | Encs[rbt->RF]->Update(dt); |
hamohamo | 0:0a9ce35078a3 | 72 | Encs[rbt->RB]->Update(dt); |
hamohamo | 0:0a9ce35078a3 | 73 | Encs[rbt->LB]->Update(dt); |
hamohamo | 8:475c17b23944 | 74 | Encs[rbt->LF]->Update(dt);*/ |
hamohamo | 0:0a9ce35078a3 | 75 | PIDs[rbt->RF]->Update(Encs[rbt->RF]->get_Omega(),w1/rbt->CWR,dt); |
hamohamo | 0:0a9ce35078a3 | 76 | PIDs[rbt->RB]->Update(Encs[rbt->RB]->get_Omega(),w2/rbt->CWR,dt); |
hamohamo | 0:0a9ce35078a3 | 77 | PIDs[rbt->LB]->Update(Encs[rbt->LB]->get_Omega(),w3/rbt->CWR,dt); |
hamohamo | 0:0a9ce35078a3 | 78 | PIDs[rbt->LF]->Update(Encs[rbt->LF]->get_Omega(),w4/rbt->CWR,dt); |
hamohamo | 8:475c17b23944 | 79 | |
hamohamo | 6:87fd489a9801 | 80 | setPWM(PIDs[rbt->RF]->getmv(),rbt->RF); |
hamohamo | 6:87fd489a9801 | 81 | setPWM(PIDs[rbt->RB]->getmv(),rbt->RB); |
hamohamo | 6:87fd489a9801 | 82 | setPWM(PIDs[rbt->LB]->getmv(),rbt->LB); |
hamohamo | 6:87fd489a9801 | 83 | setPWM(PIDs[rbt->LF]->getmv(),rbt->LF); |
hamohamo | 0:0a9ce35078a3 | 84 | } |
hamohamo | 6:87fd489a9801 | 85 | Position Core::getStatus(bool onground){ |
hamohamo | 0:0a9ce35078a3 | 86 | double vx,vy,vw; |
hamohamo | 0:0a9ce35078a3 | 87 | double vX,vY; |
hamohamo | 0:0a9ce35078a3 | 88 | double Rw1,Rw2,Rw3,Rw4; |
hamohamo | 8:475c17b23944 | 89 | Encs[rbt->F]->Update(dt); |
hamohamo | 8:475c17b23944 | 90 | Encs[rbt->R]->Update(dt); |
hamohamo | 8:475c17b23944 | 91 | Encs[rbt->B]->Update(dt); |
hamohamo | 8:475c17b23944 | 92 | Encs[rbt->L]->Update(dt); |
hamohamo | 8:475c17b23944 | 93 | Encs[rbt->RF]->Update(dt); |
hamohamo | 8:475c17b23944 | 94 | Encs[rbt->RB]->Update(dt); |
hamohamo | 8:475c17b23944 | 95 | Encs[rbt->LB]->Update(dt); |
hamohamo | 8:475c17b23944 | 96 | Encs[rbt->LF]->Update(dt); |
hamohamo | 6:87fd489a9801 | 97 | if(onground){ |
hamohamo | 6:87fd489a9801 | 98 | |
hamohamo | 6:87fd489a9801 | 99 | Rw1 = Encs[rbt->F]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 100 | Rw2 = Encs[rbt->R]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 101 | Rw3 = Encs[rbt->B]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 102 | Rw4 = Encs[rbt->L]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 103 | } |
hamohamo | 6:87fd489a9801 | 104 | else { |
hamohamo | 6:87fd489a9801 | 105 | |
hamohamo | 6:87fd489a9801 | 106 | Rw1 = Encs[rbt->RF]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 107 | Rw2 = Encs[rbt->RB]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 108 | Rw3 = Encs[rbt->LB]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 109 | Rw4 = Encs[rbt->LF]->get_Omega()*(rbt->SWR); |
hamohamo | 6:87fd489a9801 | 110 | } |
hamohamo | 0:0a9ce35078a3 | 111 | vx = (-1*Rw1 + Rw3)/2.0; |
hamohamo | 0:0a9ce35078a3 | 112 | vy = (Rw2 + -1*Rw4)/2.0; |
hamohamo | 0:0a9ce35078a3 | 113 | vw = (Rw1 + Rw2 + Rw3 + Rw4)/(rbt->C2SD)/4.0; |
hamohamo | 6:87fd489a9801 | 114 | if(onground){ |
hamohamo | 6:87fd489a9801 | 115 | vX = cos(pos.theta)*vx - sin(pos.theta)*vy; |
hamohamo | 6:87fd489a9801 | 116 | vY = sin(pos.theta)*vx + cos(pos.theta)*vy; |
hamohamo | 6:87fd489a9801 | 117 | } |
hamohamo | 6:87fd489a9801 | 118 | else { |
hamohamo | 7:c0b6afbccd97 | 119 | vX = cos(pos.theta-M_PI/4.0)*vx - sin(pos.theta-M_PI/4.0)*vy; |
hamohamo | 7:c0b6afbccd97 | 120 | vY = sin(pos.theta-M_PI/4.0)*vx + cos(pos.theta-M_PI/4.0)*vy; |
hamohamo | 6:87fd489a9801 | 121 | } |
hamohamo | 2:d88ff6dda390 | 122 | |
hamohamo | 0:0a9ce35078a3 | 123 | pos.x += (vel.x+vX)*dt/2.0; |
hamohamo | 0:0a9ce35078a3 | 124 | pos.y += (vel.y+vY)*dt/2.0; |
hamohamo | 0:0a9ce35078a3 | 125 | pos.theta += (vel.theta+vw)*dt/2.0; |
hamohamo | 0:0a9ce35078a3 | 126 | vel.x = vX; |
hamohamo | 0:0a9ce35078a3 | 127 | vel.y = vY; |
hamohamo | 0:0a9ce35078a3 | 128 | vel.theta = vw; |
hamohamo | 0:0a9ce35078a3 | 129 | return pos; |
hamohamo | 2:d88ff6dda390 | 130 | } |
hamohamo | 11:80800fd9f4af | 131 | Core::Core(Robot* robot,ScrpSlave* scrp,int mode,double dt):rbt(robot),scrp(scrp),mode(mode),dt(dt),Mots(5),Encs(9),PIDs(6),IMCs(6){} |
hamohamo | 5:8dec5e011b3c | 132 | void Core::sendPWM(double pwm,int id){scrp->send1(255, id ,(pwm * 100.0));} |
hamohamo | 2:d88ff6dda390 | 133 | void Core::sendVelocity(double Vx,double Vy,double Vw){ |
hamohamo | 2:d88ff6dda390 | 134 | double w1,w2,w3,w4; |
hamohamo | 7:c0b6afbccd97 | 135 | double vx,vy; |
hamohamo | 7:c0b6afbccd97 | 136 | vx = cos(pos.theta-M_PI/4.0)*Vx + sin(pos.theta-M_PI/4.0)*Vy; |
hamohamo | 7:c0b6afbccd97 | 137 | vy = - sin(pos.theta-M_PI/4.0)*Vx + cos(pos.theta-M_PI/4.0)*Vy; |
hamohamo | 2:d88ff6dda390 | 138 | switch(mode){ |
hamohamo | 2:d88ff6dda390 | 139 | case OMNI4: |
hamohamo | 7:c0b6afbccd97 | 140 | w1 = -vx + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 141 | w2 = vy + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 142 | w3 = vx + rbt->C2CD*Vw; |
hamohamo | 7:c0b6afbccd97 | 143 | w4 = -vy + rbt->C2CD*Vw; |
hamohamo | 2:d88ff6dda390 | 144 | break; |
hamohamo | 2:d88ff6dda390 | 145 | case OMNI3: |
hamohamo | 2:d88ff6dda390 | 146 | w1 = 0.0; |
hamohamo | 2:d88ff6dda390 | 147 | w2 = 0.0; |
hamohamo | 2:d88ff6dda390 | 148 | w3 = 0.0; |
hamohamo | 2:d88ff6dda390 | 149 | w4 = 0.0; |
hamohamo | 2:d88ff6dda390 | 150 | break; |
hamohamo | 2:d88ff6dda390 | 151 | case MECANUM: |
hamohamo | 2:d88ff6dda390 | 152 | w1 = 0.0; |
hamohamo | 2:d88ff6dda390 | 153 | w2 = 0.0; |
hamohamo | 2:d88ff6dda390 | 154 | w3 = 0.0; |
hamohamo | 2:d88ff6dda390 | 155 | w4 = 0.0; |
hamohamo | 2:d88ff6dda390 | 156 | break; |
hamohamo | 8:475c17b23944 | 157 | }/* |
hamohamo | 2:d88ff6dda390 | 158 | Encs[rbt->RF]->Update(dt); |
hamohamo | 2:d88ff6dda390 | 159 | Encs[rbt->RB]->Update(dt); |
hamohamo | 2:d88ff6dda390 | 160 | Encs[rbt->LB]->Update(dt); |
hamohamo | 8:475c17b23944 | 161 | Encs[rbt->LF]->Update(dt);*/ |
hamohamo | 10:f434b6848059 | 162 | /* |
hamohamo | 2:d88ff6dda390 | 163 | PIDs[rbt->RF]->Update(Encs[rbt->RF]->get_Omega(),w1/rbt->CWR,dt); |
hamohamo | 2:d88ff6dda390 | 164 | PIDs[rbt->RB]->Update(Encs[rbt->RB]->get_Omega(),w2/rbt->CWR,dt); |
hamohamo | 2:d88ff6dda390 | 165 | PIDs[rbt->LB]->Update(Encs[rbt->LB]->get_Omega(),w3/rbt->CWR,dt); |
hamohamo | 10:f434b6848059 | 166 | PIDs[rbt->LF]->Update(Encs[rbt->LF]->get_Omega(),w4/rbt->CWR,dt);*/ |
hamohamo | 10:f434b6848059 | 167 | |
hamohamo | 10:f434b6848059 | 168 | IMCs[rbt->RF]->Update(Encs[rbt->RF]->get_Omega(),w1/rbt->CWR,dt); |
hamohamo | 10:f434b6848059 | 169 | IMCs[rbt->RB]->Update(Encs[rbt->RB]->get_Omega(),w2/rbt->CWR,dt); |
hamohamo | 10:f434b6848059 | 170 | IMCs[rbt->LB]->Update(Encs[rbt->LB]->get_Omega(),w3/rbt->CWR,dt); |
hamohamo | 10:f434b6848059 | 171 | IMCs[rbt->LF]->Update(Encs[rbt->LF]->get_Omega(),w4/rbt->CWR,dt); |
hamohamo | 10:f434b6848059 | 172 | |
hamohamo | 10:f434b6848059 | 173 | printf("%lf,%lf,%lf\n",Encs[1]->get_Omega(),w1/rbt->CWR,IMCs[1]->getmv()); |
hamohamo | 10:f434b6848059 | 174 | /* |
hamohamo | 2:d88ff6dda390 | 175 | WAIT(0.01); |
hamohamo | 6:87fd489a9801 | 176 | sendPWM(PIDs[rbt->RF]->getmv(),rbt->RF); |
hamohamo | 2:d88ff6dda390 | 177 | WAIT(0.0125); |
hamohamo | 6:87fd489a9801 | 178 | sendPWM(PIDs[rbt->RB]->getmv(),rbt->RB); |
hamohamo | 2:d88ff6dda390 | 179 | WAIT(0.015); |
hamohamo | 6:87fd489a9801 | 180 | sendPWM(PIDs[rbt->LB]->getmv(),rbt->LB); |
hamohamo | 2:d88ff6dda390 | 181 | WAIT(0.0175); |
hamohamo | 10:f434b6848059 | 182 | sendPWM(PIDs[rbt->LF]->getmv(),rbt->LF);*/ |
hamohamo | 10:f434b6848059 | 183 | |
hamohamo | 10:f434b6848059 | 184 | WAIT(0.01); |
hamohamo | 10:f434b6848059 | 185 | sendPWM(IMCs[rbt->RF]->getmv(),rbt->RF); |
hamohamo | 10:f434b6848059 | 186 | WAIT(0.0125); |
hamohamo | 10:f434b6848059 | 187 | sendPWM(IMCs[rbt->RB]->getmv(),rbt->RB); |
hamohamo | 10:f434b6848059 | 188 | WAIT(0.015); |
hamohamo | 10:f434b6848059 | 189 | sendPWM(IMCs[rbt->LB]->getmv(),rbt->LB); |
hamohamo | 10:f434b6848059 | 190 | WAIT(0.0175); |
hamohamo | 10:f434b6848059 | 191 | sendPWM(IMCs[rbt->LF]->getmv(),rbt->LF); |
hamohamo | 0:0a9ce35078a3 | 192 | } |