ver2

Dependencies:   uw_28015 mbed move4wheel2 EC CruizCore_R6093U CruizCore_R1370P

Committer:
yuki0701
Date:
Sat Nov 16 06:26:57 2019 +0000
Revision:
1:26fc1b2f1c42
Parent:
0:b87fd8dd4322
Child:
2:820dcd23c8e3
a;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
la00noix 0:b87fd8dd4322 1 #include "EC.h"
la00noix 0:b87fd8dd4322 2 #include "R1370P.h"
la00noix 0:b87fd8dd4322 3 #include "move4wheel.h"
la00noix 0:b87fd8dd4322 4 #include "mbed.h"
la00noix 0:b87fd8dd4322 5 #include "math.h"
la00noix 0:b87fd8dd4322 6 #include "PathFollowing.h"
la00noix 0:b87fd8dd4322 7 #include "movement.h"
la00noix 0:b87fd8dd4322 8 #include "manual.h"
la00noix 0:b87fd8dd4322 9 #include "can.h"
la00noix 0:b87fd8dd4322 10
la00noix 0:b87fd8dd4322 11 #define PI 3.141592
la00noix 0:b87fd8dd4322 12
la00noix 0:b87fd8dd4322 13 //#define PROGRAM_INFO //プログラム使用時に使用プログラムの情報を最初に表示する際に定義
la00noix 0:b87fd8dd4322 14
la00noix 0:b87fd8dd4322 15 int go_waitmode = 0;
la00noix 0:b87fd8dd4322 16
yuki0701 1:26fc1b2f1c42 17 /*------------運動時の各速度の設定----------*/
yuki0701 1:26fc1b2f1c42 18 double st_speed = 500; // 移動開始時の速度
yuki0701 1:26fc1b2f1c42 19 double max_speed = 2500; // 直線移動時の最大速度
yuki0701 1:26fc1b2f1c42 20 double mid_speed = 2000; // 直線移動時の中間速度
yuki0701 1:26fc1b2f1c42 21 double turn_speed = 1000; // 旋回時の速度
yuki0701 1:26fc1b2f1c42 22 double end_speed = 200; // 停止直前の速度
yuki0701 1:26fc1b2f1c42 23 double fruit_speed = 200; // 果物を取る時の速度
yuki0701 1:26fc1b2f1c42 24 /*--------------------------------------*/
yuki0701 1:26fc1b2f1c42 25
la00noix 0:b87fd8dd4322 26 //-----mbed led------------------//点灯条件-----------------------//参照場所------------------------------//
la00noix 0:b87fd8dd4322 27 //DigitalOut cansend_led(LED1); //cansend -> on //can.cpp
la00noix 0:b87fd8dd4322 28 //DigitalOut canread_led(LED2); //canread -> on //can.cpp
la00noix 0:b87fd8dd4322 29 //DigitalOut debug_led(LED3); //maxon debug programme -> on //maxonsetting.cpp
la00noix 0:b87fd8dd4322 30
la00noix 0:b87fd8dd4322 31 //////////////////////////////////////////////////////////////以下main文/////////////////////////////////////////////////////////////////
la00noix 0:b87fd8dd4322 32
la00noix 0:b87fd8dd4322 33 int main()
la00noix 0:b87fd8dd4322 34 {
yuki0701 1:26fc1b2f1c42 35
yuki0701 1:26fc1b2f1c42 36 //UserLoopSetting_maxon();
yuki0701 1:26fc1b2f1c42 37 UserLoopSetting_sensor();
yuki0701 1:26fc1b2f1c42 38 UserLoopSetting_can();
yuki0701 1:26fc1b2f1c42 39 /*
yuki0701 1:26fc1b2f1c42 40 #ifdef PROGRAM_INFO //プログラム使用時に使用プログラムの情報を最初に表示
la00noix 0:b87fd8dd4322 41
yuki0701 1:26fc1b2f1c42 42 printf("ソースファイル名 : %s¥n", __FILE__);
yuki0701 1:26fc1b2f1c42 43 printf("作成日付 : %s¥n", __DATE__);
yuki0701 1:26fc1b2f1c42 44 printf("作成時刻 : %s¥n", __TIME__);
la00noix 0:b87fd8dd4322 45
yuki0701 1:26fc1b2f1c42 46 #endif
yuki0701 1:26fc1b2f1c42 47 */
yuki0701 1:26fc1b2f1c42 48 int move_flag = 0;
yuki0701 1:26fc1b2f1c42 49 while(1) {
yuki0701 1:26fc1b2f1c42 50
yuki0701 1:26fc1b2f1c42 51 id1_value[0] = 1;
yuki0701 1:26fc1b2f1c42 52 switch(id1_value[0]) {
yuki0701 1:26fc1b2f1c42 53 //-----auto mode----------------------------------------------------------------------------------------------------------------------//
yuki0701 1:26fc1b2f1c42 54 case 1:
yuki0701 1:26fc1b2f1c42 55
yuki0701 1:26fc1b2f1c42 56 // gogo_straight(1,1,0,0,200,0,50,500,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 57 // gogo_straight(1,1,200,0,800,0,500,500,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 58 // gogo_straight(1,1,800,0,1000,0,500,200,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 59 // mt_stop();
yuki0701 1:26fc1b2f1c42 60 // pos_correction(1000,0,0,1,1);
yuki0701 1:26fc1b2f1c42 61 // mt_stop();
yuki0701 1:26fc1b2f1c42 62 // wait(1.5);
yuki0701 1:26fc1b2f1c42 63 // gogo_straight(1,1,1000,0,800,0,200,500,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 64 // gogo_straight(1,1,800,0,200,0,500,500,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 65 // gogo_straight(1,1,200,0,0,0,500,200,5,0.1,10,0.1,50,0);
yuki0701 1:26fc1b2f1c42 66 // mt_stop();
yuki0701 1:26fc1b2f1c42 67 // pos_correction(0,0,0,1,1);
yuki0701 1:26fc1b2f1c42 68 pos_correction(50,0,0,1,1);
yuki0701 1:26fc1b2f1c42 69 mt_stop();
yuki0701 1:26fc1b2f1c42 70 move_flag = 1;
yuki0701 1:26fc1b2f1c42 71 break;
la00noix 0:b87fd8dd4322 72
yuki0701 1:26fc1b2f1c42 73 //-----wait mode----------------------------------------------------------------------------------------------------------------------//
yuki0701 1:26fc1b2f1c42 74 case 0:
yuki0701 1:26fc1b2f1c42 75
yuki0701 1:26fc1b2f1c42 76 calc_xy(0,1,1);
yuki0701 1:26fc1b2f1c42 77 ashi_led();
yuki0701 1:26fc1b2f1c42 78 //MaxonControl(0,0,0,0);
yuki0701 1:26fc1b2f1c42 79 go_waitmode = 0;
la00noix 0:b87fd8dd4322 80
yuki0701 1:26fc1b2f1c42 81 break;
yuki0701 1:26fc1b2f1c42 82 //-----manual mode--------------------------------------------------------------------------------------------------------------------//
yuki0701 1:26fc1b2f1c42 83 case 2:
la00noix 0:b87fd8dd4322 84
yuki0701 1:26fc1b2f1c42 85 ManualOut(250,100,500,200);
yuki0701 1:26fc1b2f1c42 86 go_waitmode = 0;
la00noix 0:b87fd8dd4322 87
yuki0701 1:26fc1b2f1c42 88 break;
yuki0701 1:26fc1b2f1c42 89 }
yuki0701 1:26fc1b2f1c42 90 //------------------------------------------------------------------------------------------------------------------------------------//
yuki0701 1:26fc1b2f1c42 91 if(move_flag == 1)break;
yuki0701 1:26fc1b2f1c42 92 }
yuki0701 1:26fc1b2f1c42 93
la00noix 0:b87fd8dd4322 94 }