足回り動かすためのライブラリ

使用例

#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();
}
}

motor.hpp

Committer:
hamohamo
Date:
2021-10-29
Revision:
11:80800fd9f4af
Parent:
2:d88ff6dda390

File content as of revision 11:80800fd9f4af:

#ifndef take_motor
#define take_motor

#include "mbed.h"

/*INFO
*coreを使わない場合idはなんでもいいです
*setLimitは出力するpidの上限下限を設定できます
*setPwmでpwm出力ができます
*
*/
class Motor{
public:
    Motor(PinName plus,PinName minus,int period,int id);
    ~Motor();
    void setLimit(double max,double min);
    void setPWM(double pwm);
    double get_ID();
private:
    PwmOut *Plus;
    PwmOut *Minus;
    double Max;
    double Min;
    double Pwm;
    int ID;
};

#endif