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.
Dependencies: Harurobo_CAN_1_19 mbed Maxon_setting_1_11 move4wheel2 EC PathFollowing_2_6 CruizCore_R1370P
Diff: main.cpp
- Revision:
- 1:0c9f53f5c9d0
- Parent:
- 0:f0f40dddc0c4
- Child:
- 3:112c4ddf324d
diff -r f0f40dddc0c4 -r 0c9f53f5c9d0 main.cpp
--- a/main.cpp Sat Dec 15 13:25:43 2018 +0000
+++ b/main.cpp Sat Dec 22 02:50:28 2018 +0000
@@ -3,133 +3,11 @@
#include "R1370P.h"
#include "move4wheel.h"
#include "PathFollowing.h"
-#include <stdarg.h>
-
-#define PI 3.141592
-
-#define DEBUG_MODE // compile as debug mode (comment out if you don't use)
-#ifdef DEBUG_MODE
-#define DEBUG_PRINT // enable debug_printf
-#endif
-
-Serial pc(USBTX,USBRX);
-void debug_printf(const char* format,...); // work as printf in debug
-void Debug_Control(); // control by PC keybord
-
-#define SPI_FREQ 1000000 // 1MHz
-#define SPI_BITS 16
-#define SPI_MODE 0
-#define SPI_WAIT_US 1 // 1us
-
-/*モーターの配置
-* md1//---F---\\md4
-* | |
-* L + R
-* | |
-* md2\\---B---//md3
-*/
-
-//-----mbed-----//
-SPI spi(p5,p6,p7);
-CAN can1(p30,p29,1000000);
-
-DigitalOut ss_md1(p15); //エスコンの設定
-DigitalOut ss_md2(p16);
-DigitalOut ss_md3(p17);
-DigitalOut ss_md4(p18);
-
-DigitalOut md_enable(p25);
-//DigitalIn md_ch_enable(p10); // check enable switch is open or close
-//Timer md_disable;
-DigitalOut md_stop(p24); // stop all motor
-DigitalIn md_check(p23); // check error of all motor driver //とりあえず使わない
-
-Ec EC1(p8,p26,NC,500,0.05);
-Ec EC2(p21,p22,NC,500,0.05);
-R1370P gyro(p28,p27);
-
-Ticker motor_tick; //角速度計算用ticker
-Ticker ticker; //for enc
-
-/*-----nucleo-----//
-SPI spi(PB_5,PB_4,PB_3);
-
-DigitalOut ss_md1(PB_15); //エスコンの設定
-DigitalOut ss_md2(PB_14);
-DigitalOut ss_md3(PB_13);
-DigitalOut ss_md4(PC_4);
-
-DigitalOut md_enable(PA_13); // do all motor driver enable
-//DigitalIn md_ch_enable(p10); // check enable switch is open or close
-//Timer md_disable;
-DigitalOut md_stop(PA_14); // stop all motor
-DigitalIn md_check(PB_7); // check error of all motor driver //とりあえず使わない
+#include "Maxon_setting.h"
-Ec EC1(PC_6,PC_8,NC,500,0.05);
-Ec EC2(PB_1,PB_12,NC,500,0.05);
-R1370P gyro(PC_6,PC_7);
-
-Ticker motor_tick; //角速度計算用ticker
-Ticker ticker; //for enc */
-
-
-
-//DigitalOut can_led(LED1); //if can enable -> toggle
-DigitalOut debug_led(LED2); //if debugmode -> on
-DigitalOut md_stop_led(LED3); //if motor stop -> on
-DigitalOut md_err_led(LED4); //if driver error -> on //とりあえず使わない
+CAN can1(p30,p29,1000000);
DigitalOut led(LED1);
-
-double new_dist1=0,new_dist2=0;
-double old_dist1=0,old_dist2=0;
-double d_dist1=0,d_dist2=0; //座標計算用関数
-double d_x,d_y;
-//現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済
-double start_x=0,start_y=0; //スタート位置
-
-double x_out,y_out,r_out; //出力値
-
-static int16_t m1=0, m2=0, m3=0, m4=0; //int16bit = int2byte
-
-double usw_data1,usw_data2,usw_data3,usw_data4;//CAN通信で受け取った超音波センサーの値(1000倍してあったものを0.01倍して単位を㎝から㎜に直しつつ元の値に戻す(超音波センサーは㎝で距離を読み取る))
-
-
-///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言/////////////////
-
-/*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する
- *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能)
- *(ex)
- *info.nowX.enc → エンコーダにより算出した機体位置のx座標
- *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標
-*/
-
-typedef struct{ //使用センサーの種類
- double usw; //超音波センサー
- double enc; //エンコーダ
- double gyro; //ジャイロ
- //double line;//ラインセンサー
-}robo_sensor;
-
-typedef struct{ //機体情報の種類
- robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも
- robo_sensor nowX;
- robo_sensor nowY;
-}robo_data;
-
-robo_data info={{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化
-
-
-///////////////////////////////////////////////////関数のプロトタイプ宣言////////////////////////////////////////////////////
-
-void UserLoopSetting(); // initialize setting
-void DAC_Write(int16_t data, DigitalOut* DAC_cs);
-void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4);
-
-void calOmega() //角速度計算関数
-{
- EC1.CalOmega();
- EC2.CalOmega();
-}
+Ticker ticker;
void can_read(){//CAN通信受信
@@ -139,515 +17,42 @@
if(msg.id == 1){
led = 1;
- usw_data1 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
- //printf("usw_data1 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
+ usw_data1 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
+ printf("usw_data1 = %d:%d,%lf\n\r",msg.data[0],msg.data[1],usw_data1);
}else if(msg.id == 2){
- led = 1;
- usw_data2 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
- //printf("usw_data2 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
+ //led = 1;
+ // usw_data2 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
+ //printf("usw_data2 = %d:%d,%d\n\r",msg.data[0],msg.data[1],usw_data2);
}else if(msg.id == 3){
- led = 1;
- usw_data3 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
- //printf("usw_data3 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
+ //led = 1;
+ //usw_data3 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
+ //printf("usw_data3 = %d:%d,%d\n\r",msg.data[0],msg.data[1],usw_data3);
}else if(msg.id == 4){
- led = 1;
- usw_data4 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
- //printf("usw_data4 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
+ //led = 1;
+ //usw_data4 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
+ //printf("usw_data4 = %d:%d,%d\n\r",msg.data[0],msg.data[1],usw_data4);
}
}
}
-void output(double FL,double BL,double BR,double FR)
-{
- m1=FL;
- m2=BL;
- m3=BR;
- m4=FR;
-}
-
-void base(double FL,double BL,double BR,double FR,double Max)
-//いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算
-//DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする
-{
- if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) {
-
- if (fabs(FL)>=fabs(BL)&&fabs(FL)>=fabs(BR)&&fabs(FL)>=fabs(FR))output(Max*FL/fabs(FL),Max*BL/fabs(FL),Max*BR/fabs(FL),Max*FR/fabs(FL));
- else if(fabs(BL)>=fabs(FL)&&fabs(BL)>=fabs(BR)&&fabs(BL)>=fabs(FR))output(Max*FL/fabs(BL),Max*BL/fabs(BL),Max*BR/fabs(BL),Max*FR/fabs(BL));
- else if(fabs(BR)>=fabs(FL)&&fabs(BR)>=fabs(BL)&&fabs(BR)>=fabs(FR))output(Max*FL/fabs(BR),Max*BL/fabs(BR),Max*BR/fabs(BR),Max*FR/fabs(BR));
- else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR));
- } else {
- output(FL,BL,BR,FR);
- }
-}
-
-void calc_xy() //エンコーダによる座標計算
-{
- now_angle=gyro.getAngle(); //ジャイロの値読み込み
-
- new_dist1=EC1.getDistance_mm();
- new_dist2=EC2.getDistance_mm();
- d_dist1=new_dist1-old_dist1;
- d_dist2=new_dist2-old_dist2;
- old_dist1=new_dist1;
- old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み
-
- d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180);
- d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化
- info.nowX.enc = info.nowX.enc + d_x;
- info.nowY.enc = info.nowY.enc - d_y; //微小時間毎に座標に加算
-}
-
-
-void calc_xy_usw(double tgt_angle,int xy_type,int pm_type,double xy_base){ //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない)
-//tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ)
-//xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む)
-//pm_type:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む)
-//xy_base:超音波センサーで読む壁の座標(x軸平行の壁のy座標/y軸並行の壁のx座標)
-
- double R1=130,R2=130,R3=130,R4=130; //機体の中心から各超音波センサーが付いている面までの距離
- double D1=50,D2=50,D3=50,D4=50; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離
-
- now_angle=gyro.getAngle();
-
- if(tgt_angle==0){
- if(xy_type==0 && pm_type==0){
-
- info.nowX.usw = xy_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
-
- }else if(xy_type==0 && pm_type==1){
-
- info.nowX.usw = xy_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==0){
-
- info.nowY.usw = xy_base - (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==1){
-
- info.nowY.usw = xy_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
-
- }
-
- }else if(tgt_angle==90){
- if(xy_type==0 && pm_type==0){
-
- info.nowX.usw = xy_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
-
- }else if(xy_type==0 && pm_type==1){
-
- info.nowX.usw = xy_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==0){
-
- info.nowY.usw = xy_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==1){
-
- info.nowY.usw = xy_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
-
- }
-
- }else if(tgt_angle==180){
- if(xy_type==0 && pm_type==0){
-
- info.nowX.usw = xy_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
-
- }else if(xy_type==0 && pm_type==1){
-
- info.nowX.usw = xy_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==0){
-
- info.nowY.usw = xy_base - (usw_data2+ R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
-
- }else if(xy_type==1 && pm_type==1){
-
- info.nowY.usw = xy_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
-
- }
-
- }
-
-}
-
-//ここからそれぞれのプログラム/////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-//now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
-//ジャイロの出力は角度だが三角関数はラジアンとして計算する
-//通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
-//ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
-
-void purecurve2(int type, //正面を変えずに円弧or楕円を描いて曲がる
- double point_x1,double point_y1,
- double point_x2,double point_y2,
- int theta,
- double speed,
- double q_p,double q_d,
- double r_p,double r_d,
- double r_out_max,
- double target_angle)
-//type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度
-{
- //-----PathFollowingのパラメーター設定-----//
- q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
- r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
- set_r_out(r_out_max); //旋回時の最大出力値設定関数
- set_target_angle(target_angle); //機体目標角度設定関数
-
- int s;
- int t = 0;
- double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
- double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
- double plotx[(90/theta)+1]; //楕円にとるplotのx座標
- double ploty[(90/theta)+1];
-
- double x_out,y_out,r_out;
-
- a=fabs(point_x1-point_x2);
- b=fabs(point_y1-point_y2);
-
- switch(type) {
-
- case 1://→↑移動
- X=point_x1;
- Y=point_y2;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
- ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 2://↑→移動
- X=point_x2;
- Y=point_y1;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(PI - s * (PI*theta/180));
- ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 3://↑←移動
- X=point_x2;
- Y=point_y1;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(s * (PI*theta/180));
- ploty[s] = Y + b * sin(s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 4://←↑移動
- X=point_x1;
- Y=point_y2;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
- ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 5://←↓移動
- X=point_x1;
- Y=point_y2;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
- ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 6://↓←移動
- X=point_x2;
- Y=point_y1;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(-s * (PI*theta/180));
- ploty[s] = Y + b * sin(-s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 7://↓→移動
- X=point_x2;
- Y=point_y1;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(PI + s * (PI*theta/180));
- ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
-
- case 8://→↓移動
- X=point_x1;
- Y=point_y2;
-
- for(s=0; s<((90/theta)+1); s++) {
- plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
- ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
- //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
- }
- break;
- }
-
- while(1) {
-
- calc_xy();
-
- now_x = info.nowX.enc; //カーブする時はエンコーダにより求める機体位置を100%信用
- now_y = info.nowY.enc;
-
- XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed);
- CalMotorOut(x_out,y_out,r_out);
- //debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out);
-
- base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //m1~m4に代入
- //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
-
- if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
-
- MotorControl(m1,m2,m3,m4); //出力
- debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle);
-
- if(t == (90/theta))break;
- }
-}
-
-
-void gogo_straight(double x1_point,double y1_point, //直線運動プログラム
- double x2_point,double y2_point,
- double speed1,double speed2,
- double q_p,double q_d,
- double r_p,double r_d,
- double r_out_max,
- double target_angle)
-//引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動
-{
- //-----PathFollowingのパラメーター設定-----//
- q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
- r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
- set_r_out(r_out_max); //旋回時の最大出力値設定関数
- set_target_angle(target_angle); //機体目標角度設定関数
-
- while (1) {
-
- calc_xy();
-
- XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2);
- //printf("x = %f, y = %f,angle = %f,x_out=%lf, y_out=%lf, r_out=%lf\n\r",now_x,now_y,now_angle,x_out, y_out,r_out);
-
- CalMotorOut(x_out,y_out,r_out);
- //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
-
- base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095);
- //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m1,m2,m3,m4);
-
- MotorControl(m1,m2,m3,m4);
- debug_printf("m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",m1,m2,m3,m4,now_x,now_y,now_angle);
-
- if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break;
- }
-}
-
-/*void usw_pos_correction(int type,double error,double base_x,double base_y,double x1_point,double y1_point,double x2_point,double y2_point){ //超音波センサーによる位置補正プログラム(x軸 or y軸に平行なきのみ)
-//type(1:x方向-果物アーム側/2:y方向-果物アーム/3:y方向-三宝アーム側)
-//error:補正の終了を判断するときの目標値からの許容誤差
-//base_x,base_y:超音波センサーで読む壁の座標(y軸平行の壁のx座標/x軸平行の壁のy座標)
-//x1_point,y2_point:出発地点の座標
-//x2_point,y2_point:目標地点の座標
-
-
- }*/
-
//////////////////////////////////////////////////////////////以下main文/////////////////////////////////////////////////////////////////
int main()
-{
+{
UserLoopSetting();
+ //UserLoopSetting2();
//Debug_Control()
- //purecurve2(2,start_x,start_y,500,1000,9,1000,5,0.1,10,0.1,600,0);
-
- purecurve2(5,start_x,start_y,-500,-500,9,1500,5,0.1,10,0.1,600,0);
- gogo_straight(-500,-500,-500,-1500,2000,2000,5,0.1,10,0.1,600,0);
-
- //purecurve2(3,now_x,now_y,0,2500,9,1000,5,0.1,10,0.1,600,0);
-
- MotorControl(0,0,0,0);
-}
-///////////////////////////////////////////////////////////////////////以下マクソン関連///////////////////////////////////////////////////////////////////////////
-
-void UserLoopSetting()
-{
-//------機体情報の初期化------//
-
-//info.nowX = {0,0,0};
-//info.nowY = {0,0,0};
-
-//-----エスコンの初期設定-----//
- spi.format(SPI_BITS, SPI_MODE);
- spi.frequency(SPI_FREQ);
- ss_md1 = 1;
- ss_md2 = 1;
- ss_md3 = 1;
- ss_md4 = 1;
- md_enable = 1; //enable on
- md_err_led = 0;
- md_stop = 1;
- md_stop_led = 1;
-//-----センサーの初期設定-----//
- gyro.initialize();
- motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算
- EC1.setDiameter_mm(48);
- EC2.setDiameter_mm(48); //測定輪半径//後で測定
-
-#ifdef DEBUG_MODE
- debug_led = 1;
- pc.attach(Debug_Control, Serial::RxIrq);
-#else
- debug_led = 0;
-#endif
-}
-
-#define MCP4922_AB (1<<15)
-#define MCP4922_BUF (1<<14)
-#define MCP4922_GA (1<<13)
-#define MCP4922_SHDN (1<<12)
-
-#define MCP4922_SET_OUTA (0x3000) //( MCP4922_GA || MCP4922_SHDN ) //12288
-#define MCP4922_SET_OUTB (0xB000) //( MCP4922_AB || MCP4922_GA || MCP4922_SHDN ) //45056
-#define MCP4922_MASKSET (0x0FFF) //4095
-
-void DAC_Write(int16_t data, DigitalOut* DAC_cs) //(出力,出力場所)
-{
- static uint16_t dataA; //送るデータ
- static uint16_t dataB;
-
- dataA = MCP4922_SET_OUTA;
- dataB = MCP4922_SET_OUTB;
-
- if(data >= 0) {
- if(data > 4095) {
- data = 4095;
- }
- dataA += (MCP4922_MASKSET & (uint16_t)(data));
- } else {
- if(data < -4095) {
- data = -4095;
- }
- dataB += (MCP4922_MASKSET & (uint16_t)(-data));
- }
-
- //Aの出力設定
- (DigitalOut)(*DAC_cs)=0;
- wait_us(SPI_WAIT_US);
- spi.write(dataA);
- wait_us(SPI_WAIT_US);
- (DigitalOut)(*DAC_cs)=1;
- wait_us(SPI_WAIT_US);
-
- //Bの出力設定
- (DigitalOut)(*DAC_cs)=0;
- wait_us(SPI_WAIT_US);
- spi.write(dataB);
- wait_us(SPI_WAIT_US);
- (DigitalOut)(*DAC_cs)=1;
-
-}
-void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4) //出力
-{
- static int16_t zero_check;
-
- DAC_Write(val_md1, &ss_md1);
- DAC_Write(val_md2, &ss_md2);
- DAC_Write(val_md3, &ss_md3);
- DAC_Write(val_md4, &ss_md4);
-
- zero_check = (val_md1 | val_md2 | val_md3 | val_md4); //すべての出力が0なら強制停止
- if(zero_check == 0) {
- md_stop = 1;
- md_stop_led = 1;
- } else {
- md_stop = 0;
- md_stop_led = 0;
- }
-}
-
-#ifdef DEBUG_MODE
-void Debug_Control()
-{
- static char pc_command = '\0';
-
- pc_command = pc.getc();
+ //purecurve2(5,1,1,0,0,-500,-500,9,1500,5,0.1,10,0.1,600,0);
+ //gogo_straight(1,1,0,0,500,0,2000,2000,5,0.1,10,0.1,600,0);
+
+ ticker.attach(&can_read,0.01);
+
+ while(1);
+ //printf("%f\n\r",usw_data1);
+
- if(pc_command == 'w') { //前進
- m1+=500;
- m2+=500;
- m3-=500;
- m4-=500;
- } else if(pc_command == 's') { //後進
- m1-=500;
- m2-=500;
- m3+=500;
- m4+=500;
- } else if(pc_command == 'd') { //右回り
- m1+=500;
- m2+=500;
- m3+=500;
- m4+=500;
- } else if(pc_command == 'a') { //左回り
- m1-=500;
- m2-=500;
- m3-=500;
- m4-=500;
- } else {
- m1=0;
- m2=0;
- m3=0;
- m4=0;
- }
-
- if(m1>4095) { //最大値を超えないように
- m1=4095;
- } else if(m1<-4095) {
- m1=-4095;
- }
- if(m2>4095) {
- m2=4095;
- } else if(m2<-4095) {
- m2=-4095;
- }
- if(m3>4095) {
- m3=4095;
- } else if(m3<-4095) {
- m3=-4095;
- }
- if(m4>4095) {
- m4=4095;
- } else if(m4<-4095) {
- m4=-4095;
- }
-
- debug_printf("%d %d %d %d\r\n",m1,m2,m3,m4);
- MotorControl(m1,m2,m3,m4);
- pc_command = '\0';
-}
-#endif
-
-#ifdef DEBUG_PRINT
-void debug_printf(const char* format,...)
-{
- va_list arg;
- va_start(arg, format);
- vprintf(format, arg);
- va_end(arg);
-}
-#endif
\ No newline at end of file
+ //MotorControl(0,0,0,0);
+}
\ No newline at end of file