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: mbed TrapezoidControl Pulse QEI
Revision 25:d367d1e7a153, committed 2019-09-27
- Comitter:
- Ryosei
- Date:
- Fri Sep 27 05:19:58 2019 +0000
- Parent:
- 24:370616a56815
- Commit message:
- dskb
Changed in this revision
--- a/CommonLibraries/PID/PID.h Wed Sep 18 02:03:56 2019 +0000 +++ b/CommonLibraries/PID/PID.h Fri Sep 27 05:19:58 2019 +0000 @@ -1,4 +1,4 @@ -/* + /* * PID.h * * Created: 2016/07/01 17:47:45
--- a/Input/Ultrasonic/USS/LM61CIZ.lib Wed Sep 18 02:03:56 2019 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -https://os.mbed.com/users/M_souta/code/LM61CIZ/#d2f99847b647
--- a/Input/Ultrasonic/USS/Pulse.lib Wed Sep 18 02:03:56 2019 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -https://os.mbed.com/users/NickRyder/code/Pulse/#fb79a4637a64
--- a/Input/Ultrasonic/USS/USS.cpp Wed Sep 18 02:03:56 2019 +0000
+++ /dev/null Thu Jan 01 00:00:00 1970 +0000
@@ -1,25 +0,0 @@
-#include "USS.h"
-#include "mbed.h"
-
-USS::USS(PinName echoPin, PinName trigPin, PinName tempPin)
- :echo_(echoPin), trig_(trigPin), temp_(tempPin)
-{
- distance_ = 0;
-
-}
-
-double USS::ReadDis(void) {
- int temp = temp_.getTemperature();
- double duration = echo_.read_high_us(5000);
- trig_.write_us(1,10);
- if(duration > 0){
- duration /= 2;
- double sspead = 331.5+0.6*temp;
- distance_ = duration*sspead*100/1000000;
- } else distance_ = 0;
- return distance_;
-}
-
-double USS::GetDis(void) {
- return distance_;
-}
\ No newline at end of file
--- a/Input/Ultrasonic/USS/USS.h Wed Sep 18 02:03:56 2019 +0000
+++ /dev/null Thu Jan 01 00:00:00 1970 +0000
@@ -1,20 +0,0 @@
-#ifndef USS_H_
-#define USS_H_
-
-#include "mbed.h"
-#include "LM61CIZ.h"
-#include "Pulse.h"
-
-class USS {
- public:
- USS(PinName echoPin, PinName trigPin, PinName tempPin);
- double ReadDis(void);
- double GetDis(void);
- private:
- float distance_;
- PulseInOut echo_;
- PulseInOut trig_;
- LM61CIZ temp_;
-};
-
-#endif //ULTRASONI_H_
\ No newline at end of file
--- a/Input/Ultrasonic/Ultrasonic.cpp Wed Sep 18 02:03:56 2019 +0000
+++ /dev/null Thu Jan 01 00:00:00 1970 +0000
@@ -1,10 +0,0 @@
-#include "Ultrasonic.h"
-
-namespace ULTRASONIC {
-
-
-
-
-
-
-}
\ No newline at end of file
--- a/Input/Ultrasonic/Ultrasonic.h Wed Sep 18 02:03:56 2019 +0000
+++ /dev/null Thu Jan 01 00:00:00 1970 +0000
@@ -1,18 +0,0 @@
-#ifndef ULTRASONIC_H_
-#define ULTRASONIC_H_
-
-#include "USS.h"
-
-#define ECHO_0 PC_3
-#define ECHO_1 PC_1
-
-#define TRIG_0 PC_0
-#define TRIG_1 PB_0
-
-#define TEMP PC_2
-
-namespace ULTRASONIC {
-
-}
-
-#endif //ULREASONIC_H_
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Pulse.lib Fri Sep 27 05:19:58 2019 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/NickRyder/code/Pulse/#fb79a4637a64
--- a/System/Process/Process.cpp Wed Sep 18 02:03:56 2019 +0000
+++ b/System/Process/Process.cpp Fri Sep 27 05:19:58 2019 +0000
@@ -1,7 +1,39 @@
+///////////////////////////////////////////////////////////////////////
+/*
+三浦先輩へ
+主に変えたところ
+・超音波センサーの値取得の関数化
+・PulseInOutライブラリを導入
+・LedOut()関数を追加
+
+の3つです。他にも変えたところがあるかもしれないので、確認お願いします。
+また、ソレノイドハブとの通信は書いていません。洗濯ばさみの電磁弁はNRPの時の例のアレで動かしています。
+普通にピン数が足りないため、ソレノイドハブでプログラムを動かすことを強く望みます。
+Process.hの確認もよくお願いします。
+LedOutですが、現在は
+LedOut(0)=金色光りっぱなし
+LedOut(1)=旧式の光り方
+LedOut(2)=ゾーン色で光りっぱなし
+LedOut(3)=ゾーン色でふわんふわん
+となっています。希望があれば追加します。無ければ適当に引数が増えるごとに光り方をうざくしていきます。
+温度センサーですが、調子が悪いため、直で温度の変数を設定してください。
+////////////////////////////////////////////////////////////////////////////////////////
+*/
+////////////////////////////////
+/*
+2019/09/24
+Process.cpp
+Auther:Miyagawa Ryosei
+
+*/
+////////////////////////////////
#include "mbed.h"
#include "Process.h"
+#include "Pulse.h"////////////こいつ
+
+
#include "../../CommonLibraries/PID/PID.h"
#include "../../Communication/RS485/ActuatorHub/ActuatorHub.h"
#include "../../Communication/RS485/LineHub/LineHub.h"
@@ -9,7 +41,7 @@
#include "../../Input/ExternalInt/ExternalInt.h"
#include "../../Input/Switch/Switch.h"
#include "../../Input/Encoder/Encoder.h"
-#include "../../Input/Ultrasonic/Ultrasonic.h"
+//#include "../../Input/Ultrasonic/Ultrasonic.h"
#include "../../LED/LED.h"
#include "../../Safty/Safty.h"
#include "../Using.h"
@@ -17,7 +49,7 @@
using namespace SWITCH;
using namespace PID_SPACE;
using namespace ENCODER;
-using namespace ULTRASONIC;
+//using namespace ULTRSONIC;
using namespace LINEHUB;
@@ -38,12 +70,12 @@
#pragma region USER-DEFINED_VARIABLES_AND_PROTOTYPE
/*Replace here with the definition code of your variables.*/
-
+/*
USS ultrasonic[] = {
USS(ECHO_0,TRIG_0,TEMP),
USS(ECHO_1,TRIG_1,TEMP),
};
-
+*/
Serial pc(USBTX, USBRX);
//**************Buzzer****************
@@ -75,10 +107,10 @@
//*************tire*************
PID rotaconPID[] = {
- PID(0.0001,-1,1,0.05,0,0), //LF
- PID(0.0001,-1,1,0.05,0,0), //LB
- PID(0.0001,-1,1,0.05,0,0), //RB
- PID(0.0001,-1,1,0.05,0,0), //RF
+ PID(0.0001,-1,1,0.05,0,0), //LF
+ PID(0.0001,-1,1,0.05,0,0), //LB
+ PID(0.0001,-1,1,0.05,0,0), //RB
+ PID(0.0001,-1,1,0.05,0,0), //RF
};
#define FL 0
@@ -92,9 +124,9 @@
const float ucR = 420.0; //中心からのタイヤの距離
typedef struct {
- float Vx; //X方向の速度
- float Vy; //Y方向の速度
- float Va; //角速度
+ float Vx; //X方向の速度
+ float Vy; //Y方向の速度
+ float Va; //角速度
} Vvector;
Vvector move; //進む速度
@@ -151,39 +183,92 @@
// ************* Line ************** //
-const int omni[15][15] =
-{
-{ 0, 5, 21, 47, 83, 130, 187, 255, 255, 255, 255, 255, 255, 255, 255 },
-{ -5, 0, 5, 21, 47, 83, 130, 187, 193, 208, 234, 255, 255, 255, 255 },
-{ -21, -5, 0, 5, 21, 47, 83, 130, 135, 151, 177, 213, 255, 255, 255 },
-{ -47, -21, 5, 0, 5, 21, 47, 83, 88, 104, 130, 167, 213, 255, 255 },
-{ -83, -47, -21, 5, 0, 5, 21, 47, 52, 68, 94, 130, 177, 234, 255 },
-{ -130, -83, -47, -21, 5, 0, 5, 21, 26, 42, 68, 104, 151, 208, 255 },
-{ -187, -130, -83, -47, -21, -5, 0, 5, 10, 26, 52, 88, 135, 193, 255 },
-{ -255, -187, -130, -83, -47, -21, -5, 0, 5, 21, 47, 83, 130, 187, 255 },
-{ -255, -193, -135, -88, -52, -26, -10, -5, 0, 5, 21, 47, 83, 130, 187 },
-{ -255, -208, -151, -104, -68, -42, -26, -21, -5, 0, 5, 21, 47, 83, 130 },
-{ -255, -234, -177, -130, -94, -68, -52, -47, -21, -7, 0, 7, 21, 47, 83 },
-{ -255, -255, -213, -167, -130, -104, -88, -83, -47, -21, -5, 0, 5, 21, 47 },
-{ -255, -255, -255, -213, -177, -151, -135, -130, -83, -47, -21, -5, 0, 5, 21 },
-{ -255, -255, -255, -255, -234, -208, -193, -187, -130, -83, -47, -21, -5, 0, 5 },
-{ -255, -255, -255, -255, -255, -255, -255, -255, -187, -130, -83, -47, -21, -5, 0 }
+const int omni[15][15] = {
+ { 0, 5, 21, 47, 83, 130, 187, 255, 255, 255, 255, 255, 255, 255, 255 },
+ { -5, 0, 5, 21, 47, 83, 130, 187, 193, 208, 234, 255, 255, 255, 255 },
+ { -21, -5, 0, 5, 21, 47, 83, 130, 135, 151, 177, 213, 255, 255, 255 },
+ { -47, -21, 5, 0, 5, 21, 47, 83, 88, 104, 130, 167, 213, 255, 255 },
+ { -83, -47, -21, 5, 0, 5, 21, 47, 52, 68, 94, 130, 177, 234, 255 },
+ { -130, -83, -47, -21, 5, 0, 5, 21, 26, 42, 68, 104, 151, 208, 255 },
+ { -187, -130, -83, -47, -21, -5, 0, 5, 10, 26, 52, 88, 135, 193, 255 },
+ { -255, -187, -130, -83, -47, -21, -5, 0, 5, 21, 47, 83, 130, 187, 255 },
+ { -255, -193, -135, -88, -52, -26, -10, -5, 0, 5, 21, 47, 83, 130, 187 },
+ { -255, -208, -151, -104, -68, -42, -26, -21, -5, 0, 5, 21, 47, 83, 130 },
+ { -255, -234, -177, -130, -94, -68, -52, -47, -21, -7, 0, 7, 21, 47, 83 },
+ { -255, -255, -213, -167, -130, -104, -88, -83, -47, -21, -5, 0, 5, 21, 47 },
+ { -255, -255, -255, -213, -177, -151, -135, -130, -83, -47, -21, -5, 0, 5, 21 },
+ { -255, -255, -255, -255, -234, -208, -193, -187, -130, -83, -47, -21, -5, 0, 5 },
+ { -255, -255, -255, -255, -255, -255, -255, -255, -187, -130, -83, -47, -21, -5, 0 }
};
const int curve[15] = { -204, -150, -104, -66, -38, -17, -4, 0, 4, 17, 38, 66, 104, 150, 204 };
uint8_t SetStatus(int);
-uint8_t SetStatus(int pwmVal) {
- if (pwmVal < 0) return BACK;
- else if (pwmVal > 0) return FOR;
- else if (pwmVal == 0) return BRAKE;
- else return BRAKE;
+uint8_t SetStatus(int pwmVal)
+{
+ if (pwmVal < 0) return BACK;
+ else if (pwmVal > 0) return FOR;
+ else if (pwmVal == 0) return BRAKE;
+ else return BRAKE;
}
uint8_t SetPWM(int);
-uint8_t SetPWM(int pwmVal) {
- if (pwmVal == 0 || pwmVal > 255 || pwmVal < -255) return 255;
- else return abs(pwmVal);
+uint8_t SetPWM(int pwmVal)
+{
+ if (pwmVal == 0 || pwmVal > 255 || pwmVal < -255) return 255;
+ else return abs(pwmVal);
}
+//*********Ultra-Sound sensor***************
+AnalogIn Temp(TEMP);
+//double temp=( Temp.read()* 3.3 - 0.6) / 0.01;
+PulseInOut Echo0(ECHO_0);
+PulseInOut Echo1(ECHO_1);
+PulseInOut Trig0(TRIG_0);
+PulseInOut Trig1(TRIG_1);
+double UltraRead(int num)
+{
+ double Distance=0;
+ double Duration=0;
+ double temp=21;////////////////////////////////////////////////温度
+ if(num==0) {
+ Trig0.write_us(1,10);
+ Duration=Echo0.read_high_us(5000);
+ } else if(num==1) {
+ Trig1.write_us(1,10);
+ Duration=Echo1.read_high_us(5000);
+ }
+ if(Duration>0) {
+ Duration=Duration/2;
+ double sspead=331.5+0.6*temp;
+ Distance=Duration*sspead*100/1000000;
+ } else {
+ return 0;
+ }
+ return Distance;
+}
+//*********Ultra-Sound sensor***************
+
+//*********Tape LED**************************
+DigitalOut select1(SELECT_1);
+DigitalOut select2(SELECT_2);
+DigitalOut select3(SELECT_3);
+void LedOut(int num)
+{
+ int selectnum[8][3]= {
+ {0,0,0},
+ {0,0,1},
+ {0,1,0},
+ {0,1,1},
+ {1,0,0},
+ {1,0,1},
+ {1,1,0},
+ {1,1,1}
+ };
+ select1=selectnum[num][0];
+ select2=selectnum[num][1];
+ select3=selectnum[num][2];
+}
+//*********Tape LED**************************
+
#pragma endregion USER-DEFINED_VARIABLES_AND_PROTOTYPE
@@ -222,654 +307,1186 @@
void SystemProcessInitialize()
{
- #pragma region USER-DEFINED_VARIABLE_INIT
- /*Replace here with the initialization code of your variables.*/
- rotaconPIDtimer.attach(tirePID,0.1);
-
- #pragma endregion USER-DEFINED_VARIABLE_INIT
+ #pragma region USER-DEFINED_VARIABLE_INIT
+ /*Replace here with the initialization code of your variables.*/
+ rotaconPIDtimer.attach(tirePID,0.1);
- lock = true;
- processChangeComp = true;
- current = DEFAULT_PROCESS;
+ #pragma endregion USER-DEFINED_VARIABLE_INIT
+
+ lock = true;
+ processChangeComp = true;
+ current = DEFAULT_PROCESS;
- #ifdef USE_SUBPROCESS
- #if USE_PROCESS_NUM>0
- Process[0] = Process0;
- #endif
- #if USE_PROCESS_NUM>1
- Process[1] = Process1;
- #endif
- #if USE_PROCESS_NUM>2
- Process[2] = Process2;
- #endif
- #if USE_PROCESS_NUM>3
- Process[3] = Process3;
- #endif
- #if USE_PROCESS_NUM>4
- Process[4] = Process4;
- #endif
- #if USE_PROCESS_NUM>5
- Process[5] = Process5;
- #endif
- #if USE_PROCESS_NUM>6
- Process[6] = Process6;
- #endif
- #if USE_PROCESS_NUM>7
- Process[7] = Process7;
- #endif
- #if USE_PROCESS_NUM>8
- Process[8] = Process8;
- #endif
- #if USE_PROCESS_NUM>9
- Process[9] = Process9;
- #endif
- #endif
+#ifdef USE_SUBPROCESS
+#if USE_PROCESS_NUM>0
+ Process[0] = Process0;
+#endif
+#if USE_PROCESS_NUM>1
+ Process[1] = Process1;
+#endif
+#if USE_PROCESS_NUM>2
+ Process[2] = Process2;
+#endif
+#if USE_PROCESS_NUM>3
+ Process[3] = Process3;
+#endif
+#if USE_PROCESS_NUM>4
+ Process[4] = Process4;
+#endif
+#if USE_PROCESS_NUM>5
+ Process[5] = Process5;
+#endif
+#if USE_PROCESS_NUM>6
+ Process[6] = Process6;
+#endif
+#if USE_PROCESS_NUM>7
+ Process[7] = Process7;
+#endif
+#if USE_PROCESS_NUM>8
+ Process[8] = Process8;
+#endif
+#if USE_PROCESS_NUM>9
+ Process[9] = Process9;
+#endif
+#endif
}
static void SystemProcessUpdate()
{
- #ifdef USE_SUBPROCESS
- if(controller->Button.HOME) lock = false;
-
- if(controller->Button.START && processChangeComp)
- {
- current++;
- if (USE_PROCESS_NUM < current) current = USE_PROCESS_NUM;
- processChangeComp = false;
- }
- else if(controller->Button.SELECT && processChangeComp)
- {
- current--;
- if (current < 0) current = 0;
- processChangeComp = false;
- }
- else if(!controller->Button.SELECT && !controller->Button.START) processChangeComp = true;
- #endif
-
- #ifdef USE_MOTOR
- ACTUATORHUB::MOTOR::Motor::Update(motor);
- #endif
-
- #ifdef USE_SOLENOID
- ACTUATORHUB::SOLENOID::Solenoid::Update(solenoid);
- #endif
+#ifdef USE_SUBPROCESS
+ if(controller->Button.HOME) lock = false;
+
+ if(controller->Button.START && processChangeComp) {
+ current++;
+ if (USE_PROCESS_NUM < current) current = USE_PROCESS_NUM;
+ processChangeComp = false;
+ } else if(controller->Button.SELECT && processChangeComp) {
+ current--;
+ if (current < 0) current = 0;
+ processChangeComp = false;
+ } else if(!controller->Button.SELECT && !controller->Button.START) processChangeComp = true;
+#endif
- #ifdef USE_RS485
- ACTUATORHUB::ActuatorHub::Update();
- //LINEHUB::LineHub::Update();
- #endif
-
+#ifdef USE_MOTOR
+ ACTUATORHUB::MOTOR::Motor::Update(motor);
+#endif
+
+#ifdef USE_SOLENOID
+ ACTUATORHUB::SOLENOID::Solenoid::Update(solenoid);
+#endif
+
+#ifdef USE_RS485
+ ACTUATORHUB::ActuatorHub::Update();
+ //LINEHUB::LineHub::Update();
+#endif
+
}
+double Ult_left=UltraRead(0);///////////////////////////////////////////left sensor
+double Ult_right=UltraRead(1);//////////////////////////////////////////right sensor
+
void SystemProcess()
{
- SystemProcessInitialize();
+ SystemProcessInitialize();
+
+ while(1) {
+ int g[8];
+ for(int i = 0; i < 8; i++) {
+ g[i] = lineCast(LineHub::GetPara(i));
+ }
+ Ult_left=UltraRead(0);//////////////////////////////////////////left sensor
+ Ult_right=UltraRead(1);//////////////////////////////////////////right sensor
+
+
+// pc.printf("1:%d 2:%d 3:%d 4:%d 5:%d 6:%d 7:%d 8:%d ULTRA0:%lf ULTRA1:%lf 1-2:%lf:\n\r",g[0],g[1],g[2],g[3],g[4],g[5],g[6],g[7],Ult_left,Ult_right,Ult_left-Ult_right);
- while(1)
- {
- int g[8];
- for(int i = 0; i < 8; i++){
- g[i] = lineCast(LineHub::GetPara(i));
- }
-
- pc.printf("1:%d 2:%d 3:%d 4:%d 5:%d 6:%d 7:%d 8:%d\n\r",g[0],g[1],g[2],g[3],g[4],g[5],g[6],g[7]);
-
- //float a = ultrasonic[0].ReadDis();
- //pc.printf("%f\n\r",a);
-
- //int ppap = encoder[0].getPulses();
- //pc.printf("%d\n\r",ppap);
-
-
- buzzer.period(1.0/800);
-
- #ifdef USE_MU
- controller = CONTROLLER::Controller::GetData();
- #endif
+ //float a = ultrasonic[0].ReadDis();
+ //pc.printf("%f\n\r",a);
+
+ //int ppap = encoder[0].getPulses();
+ //pc.printf("%d\n\r",ppap);
+
+
+ buzzer.period(1.0/800);
+
+#ifdef USE_MU
+ controller = CONTROLLER::Controller::GetData();
+#endif
- #ifdef USE_ERRORCHECK
- if(SAFTY::ErrorCheck::Check() & SAFTY::Error::ControllerLost)
- {
- CONTROLLER::Controller::DataReset();
- AllActuatorReset();
- lock = true;
- }
- else
- #endif
- {
+#ifdef USE_ERRORCHECK
+ if(SAFTY::ErrorCheck::Check() & SAFTY::Error::ControllerLost) {
+ CONTROLLER::Controller::DataReset();
+ AllActuatorReset();
+ lock = true;
+ } else
+#endif
+ {
- #ifdef USE_SUBPROCESS
- if(!lock)
- {
- Process[current]();
- }
- else
- #endif
- {
- //ロック時の処理
- }
- }
-
-
- //Emergency!
- /*
- if(!EMG_0 && !EMG_1 && !EMGflag){
- buzzer = 0;
- BuzzerTimer.attach(BuzzerTimer_func, 1);
- EMGflag = true;
- LED_DEBUG0 = 1;
- }
- if(EMG_0 && EMG_1 && EMGflag){
- buzzer = 1;
- BuzzerTimer.detach();
- EMGflag = false;
- }
- */
- SystemProcessUpdate();
- }
+#ifdef USE_SUBPROCESS
+ if(!lock) {
+ Process[current]();
+ } else
+#endif
+ {
+ //ロック時の処理
+ }
+ }
+
+
+ //Emergency!
+ /*
+ if(!EMG_0 && !EMG_1 && !EMGflag){
+ buzzer = 0;
+ BuzzerTimer.attach(BuzzerTimer_func, 1);
+ EMGflag = true;
+ LED_DEBUG0 = 1;
+ }
+ if(EMG_0 && EMG_1 && EMGflag){
+ buzzer = 1;
+ BuzzerTimer.detach();
+ EMGflag = false;
+ }
+ */
+ SystemProcessUpdate();
+ }
}
-
+
#pragma region PROCESS
#ifdef USE_SUBPROCESS
#if USE_PROCESS_NUM>0
-static void Process0()
-{
- AllActuatorReset();
+static void Process0()
+{
+ AllActuatorReset();
}
#endif
-
+DigitalOut CLOTHESPIN(PB_9);
#if USE_PROCESS_NUM>1
static void Process1()
{
-
+ LedOut(1);
PIDflag = false;
-
+ if(controller->Button.ZR) {
+ CLOTHESPIN = 1;
+ } else {
+ CLOTHESPIN=0;
+ }
+
if(controller->Button.UP) {
- motor[LIFT_LB].dir = FOR;
- motor[LIFT_LB].pwm = 190;
- motor[LIFT_RB].dir = BACK;
- motor[LIFT_RB].pwm = 180;
+ motor[LIFT_LB].dir = FOR;
+ motor[LIFT_LB].pwm = 190;
+ motor[LIFT_RB].dir = BACK;
+ motor[LIFT_RB].pwm = 180;
} else if(controller->Button.DOWN) {
- motor[LIFT_LB].dir = BACK;
- motor[LIFT_LB].pwm = 180;
- motor[LIFT_RB].dir = FOR;
- motor[LIFT_RB].pwm = 190;
+ motor[LIFT_LB].dir = BACK;
+ motor[LIFT_LB].pwm = 180;
+ motor[LIFT_RB].dir = FOR;
+ motor[LIFT_RB].pwm = 190;
} else if(controller->Button.LEFT) {
- motor[LIFT_LB].dir = FOR;
- motor[LIFT_LB].pwm = 180;
+ motor[LIFT_LB].dir = FOR;
+ motor[LIFT_LB].pwm = 180;
} else if(controller->Button.RIGHT) {
- motor[LIFT_RB].dir = BACK;
- motor[LIFT_RB].pwm = 180;
+ motor[LIFT_RB].dir = BACK;
+ motor[LIFT_RB].pwm = 180;
} else {
- motor[LIFT_LB].dir = FREE;
- motor[LIFT_LB].pwm = 255;
- motor[LIFT_RB].dir = BACK;
- motor[LIFT_RB].pwm = 10;
- }
-
-
- if(controller->Button.X) {
- motor[LIFT_U].dir = FOR;
- motor[LIFT_U].pwm = 180;
- } else if(controller->Button.Y) {
- motor[LIFT_U].dir = BACK;
- motor[LIFT_U].pwm = 180;
- } else {
- motor[LIFT_U].dir = BRAKE;
- motor[LIFT_U].pwm = 180;
+ motor[LIFT_LB].dir = FREE;
+ motor[LIFT_LB].pwm = 255;
+ motor[LIFT_RB].dir = BACK;
+ motor[LIFT_RB].pwm = 10;
}
- if(!(controller->AnalogL.Y == 7) || !(controller->AnalogL.X == 7)) {
- motor[TIRE_BL].dir = SetStatus(-omni[controller->AnalogL.Y][14-controller->AnalogL.X] );
- motor[TIRE_FL].dir = SetStatus(omni[controller->AnalogL.Y][controller->AnalogL.X] );
- motor[TIRE_BR].dir = SetStatus(-omni[14-controller->AnalogL.X][14-controller->AnalogL.Y] );
- motor[TIRE_FR].dir = SetStatus(omni[controller->AnalogL.X][14-controller->AnalogL.Y] );
-
- motor[TIRE_FR].pwm = SetPWM(omni[controller->AnalogL.Y][14-controller->AnalogL.X] * 0.2) ;
- motor[TIRE_FL].pwm = SetPWM(omni[controller->AnalogL.Y][controller->AnalogL.X] * 0.2) ;
- motor[TIRE_BR].pwm = SetPWM(omni[14-controller->AnalogL.X][14-controller->AnalogL.Y] * 0.2) ;
- motor[TIRE_BL].pwm = SetPWM(omni[controller->AnalogL.X][14-controller->AnalogL.Y] * 0.2) ;
- } else {
- motor[TIRE_BL].dir = SetStatus(curve[controller->AnalogR.X]);
- motor[TIRE_FL].dir = SetStatus(curve[controller->AnalogR.X]);
- motor[TIRE_BR].dir = SetStatus(curve[controller->AnalogR.X]);
- motor[TIRE_FR].dir = SetStatus(curve[controller->AnalogR.X]);
-
- motor[TIRE_FR].pwm = SetPWM(curve[controller->AnalogR.X]);
- motor[TIRE_FL].pwm = SetPWM(curve[controller->AnalogR.X]);
- motor[TIRE_BR].pwm = SetPWM(curve[controller->AnalogR.X]);
- motor[TIRE_BL].pwm = SetPWM(curve[controller->AnalogR.X]);
- }
+
+ if(controller->Button.X) {
+ motor[LIFT_U].dir = FOR;
+ motor[LIFT_U].pwm = 180;
+ } else if(controller->Button.Y) {
+ motor[LIFT_U].dir = BACK;
+ motor[LIFT_U].pwm = 180;
+ } else {
+ motor[LIFT_U].dir = BRAKE;
+ motor[LIFT_U].pwm = 180;
+ }
+
+ if(!(controller->AnalogL.Y == 7) || !(controller->AnalogL.X == 7)) {
+ motor[TIRE_FR].dir = SetStatus(-omni[controller->AnalogL.Y][14-controller->AnalogL.X] );
+ motor[TIRE_FL].dir = SetStatus(omni[controller->AnalogL.Y][controller->AnalogL.X] );
+ motor[TIRE_BR].dir = SetStatus(-omni[14-controller->AnalogL.X][14-controller->AnalogL.Y] );
+ motor[TIRE_BL].dir = SetStatus(omni[controller->AnalogL.X][14-controller->AnalogL.Y] );
+
+ motor[TIRE_FR].pwm = SetPWM(omni[controller->AnalogL.Y][14-controller->AnalogL.X] * 0.2) ;
+ motor[TIRE_FL].pwm = SetPWM(omni[controller->AnalogL.Y][controller->AnalogL.X] * 0.2) ;
+ motor[TIRE_BR].pwm = SetPWM(omni[14-controller->AnalogL.X][14-controller->AnalogL.Y] * 0.2) ;
+ motor[TIRE_BL].pwm = SetPWM(omni[controller->AnalogL.X][14-controller->AnalogL.Y] * 0.2) ;
+ } else {
+ motor[TIRE_BL].dir = SetStatus(curve[controller->AnalogR.X]);
+ motor[TIRE_FL].dir = SetStatus(curve[controller->AnalogR.X]);
+ motor[TIRE_BR].dir = SetStatus(curve[controller->AnalogR.X]);
+ motor[TIRE_FR].dir = SetStatus(curve[controller->AnalogR.X]);
+
+ motor[TIRE_FR].pwm = SetPWM(curve[controller->AnalogR.X]);
+ motor[TIRE_FL].pwm = SetPWM(curve[controller->AnalogR.X]);
+ motor[TIRE_BR].pwm = SetPWM(curve[controller->AnalogR.X]);
+ motor[TIRE_BL].pwm = SetPWM(curve[controller->AnalogR.X]);
+ }
+
}
#endif
#if USE_PROCESS_NUM>2
static void Process2()
-{
-/*
- if(moving) {
- if(LimiSw::IsPressed(LSW_LB)) {
- if(switchFlag_LB) {
- switchFlag_LB = false;
- motor[LIFT_LB].dir = BRAKE;
- motor[LIFT_LB].pwm = 200;
- } else {
- seitchFlag_LB = true;
- }
- }
- if(LimiSw::IsPressed(LSW_RB)) {
- if(switchFlag_RB) {
- switchFlag_RB = false;
- motor[LIFT_RB].dir = BRAKE;
- motor[LIFT_RB].pwm = 200;
- } else {
- seitchFlag_RB = true;
- }
- }
- if(motor[LIFT_LB].dir == BRAKE && motor[LIFT_RB].dir == BRAKE) moving = false;
- } else {
- if(controller->Button.UP) {
- if(!(state == UPPER)) {
- state++;
- motor[LIFT_LB].dir = BACK;
- motor[LIFT_RB].dir = FOR;
- motor[LIFT_LB].pwm = 200;
- motor[LIFT_RB].pwm = 200;
- }
- } else if(controller->Button.DOWN) {
- if(!(state == LOWER)) {
- state--;
- moving = true;
- motor[LIFT_LB].dir = FOR;
- motor[LIFT_RB].dir = BACK;
- motor[LIFT_LB].pwm = 200;
- motor[LIFT_RB].pwm = 200;
- }
- } else {
- motor[LIFT_LB].dir = BRAKE;
- motor[LIFT_RB].dir = BRAKE;
- motor[LIFT_LB].pwm = 200;
- motor[LIFT_RB].pwm = 200;
- }
- }
-*/
+{
+
+ static int phase=0;//system phase
+ static int StartFlag=0;//if start switch is pressed,the valiable sets "1".
+ pc.printf("phase:%d,air:%d\r\n",phase,CLOTHESPIN);
+ Timer FlagTimer;//調整中に超音波センサーが変な動きをした時のためのタイマー
+ Timer AirTimer;//エアーのタイマー
+ int RedOrBlue=LimitSw::IsPressed(RED_OR_BLUE);
+// solenoid.solenoid0=1;
+ if(LimitSw::IsPressed(STARTSW)) {
+ CLOTHESPIN=0;
+ StartFlag=1;
+ }
+ if(controller->Button.ZL) {
+ CLOTHESPIN=0;
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=15;
+ } else {
+ CLOTHESPIN=0;
+ }
+ if((controller->Button.A)||(StartFlag==1)) {
+ if(phase==0) {
+ //位置調整
+ //(P制御)
+ CLOTHESPIN=0;
+ LedOut(4);
+ if((Ult_left>0)&&(Ult_right>0)) {//データを受け取っているとき
+ if((Ult_left<16)&&(Ult_left>14)&&(Ult_right<16)&&(Ult_right>14)) { //合った場合
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ phase=1;//system phase increasing
+ } else if((Ult_left<16)&&(Ult_left>14)) { //Ult_leftのみあった場合
+ if(Ult_right>16) { //Ult_rightが遠い場合
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=15;
+ } else if(Ult_right<14) { //Ult_rightが近い場合
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=15;
+ }
+ } else if((Ult_right<16)&&(Ult_right>14)) { //Ult_rightのみあった場合
+ if(Ult_left>16) { //Ult_leftが遠い場合
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=0;
+ } else if(Ult_left<14) { //Ult_leftが近い場合
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=0;
+ }
+ } else { //どっちもあってない場合
+ if( (Ult_left+Ult_right)<=25||(Ult_left+Ult_right)>=35) {//離れすぎているor近すぎるとき
+ if((Ult_left-Ult_right)>10||((Ult_left-Ult_right)<-10) ) { //傾きが大きいとき
+ if((Ult_left-Ult_right)>0) { //Ult_leftの方が後ろに来ているとき
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=15;
+ } else if((Ult_left-Ult_right)<=0) { //Ult_rightの方が後ろに来ているとき
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=15;
+ }
+ } else { //傾きが大きくなくて離れているとき
+ if((Ult_right+Ult_left)<=25) { //近すぎるとき
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=20;
+ motor[TIRE_FR].pwm=20;
+ motor[TIRE_BL].pwm=20;
+ motor[TIRE_BR].pwm=20;
+ } else if((Ult_right+Ult_left)>=35) { //離れているとき
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=20;
+ motor[TIRE_FR].pwm=20;
+ motor[TIRE_BL].pwm=20;
+ motor[TIRE_BR].pwm=20;
+ }
+ }
+
+ } else { //さほど離れてはいないが傾きが大きいとき
+ if((Ult_left-Ult_right)>0) { //Ult_leftの方が後ろに来ているとき
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=15;
+ } else if((Ult_left-Ult_right)<=0) { //Ult_rightの方が後ろに来ているとき
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=15;
+ motor[TIRE_FR].pwm=15;
+ motor[TIRE_BL].pwm=15;
+ motor[TIRE_BR].pwm=15;
+ }
+ }
+ }
+
+ } else {//データを受け取ってないとき
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ }
+ } else if(phase==1) {
+ phase=2;
+
+
+ //待機&phase1に戻る
+
+ } else if(phase==2) {
+ CLOTHESPIN=SOLENOID_OFF;
+ LedOut(1);
+ //リミットスイッチに当てる
+ static int count2=0;
+ if(count2==0) {
+ if((Ult_left>0)&&(Ult_right>0)) {//データを受け取っているとき
+ if( (Ult_left+Ult_right)<=25||(Ult_left+Ult_right)>=35) {
+ if(((Ult_left-Ult_right)>=5)||((Ult_left-Ult_right)<=-5)) {
+ if(Ult_left-Ult_right<=0) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+
+ motor[TIRE_FL].pwm=25+(-1*(Ult_left-Ult_right));
+ motor[TIRE_FR].pwm=25+(-1*(Ult_left-Ult_right));
+
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25;
+ } else if(Ult_left-Ult_right>0) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_BL].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_BR].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25;
+ }
+ } else if((Ult_left+Ult_right)<=25) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=25;
+ } else if((Ult_left+Ult_right)>=35) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=25;
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=0;
+ }
+ } else {
+ if(Ult_left-Ult_right<=0) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+
+ motor[TIRE_FL].pwm=25+(-1*(Ult_left-Ult_right));
+ motor[TIRE_FR].pwm=25+(-1*(Ult_left-Ult_right));
+
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25;
+ } else if(Ult_left-Ult_right>0) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_BL].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_BR].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25;
+ }
+ }
+
+ } else {
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+
+ }
+ if(LimitSw::IsPressed(LEFTlim)) {
+ count2=1;
+ }
+
+ } else if(count2==1) {
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=255;
+ motor[TIRE_FR].pwm=255;
+ motor[TIRE_BL].pwm=255;
+ motor[TIRE_BR].pwm=255;
+ phase=10;
+ }
+ } else if(phase==3) {
+ //洗濯ばさみを止める&戻す
+ static int count3=0;
+ static int loop=0;
+ pc.printf("%d\r\n",loop);
+ CLOTHESPIN=1;
+ if(count3==0) {
+ loop++;
+ if(loop==60) {
+ count3=1;
+ }
+ } else if(count3==1) {
+ CLOTHESPIN=0;
+ phase=4;
+
+ }
+ } else if(phase==4) {
+ //シーツをかける
+ LedOut(3);
+ CLOTHESPIN=0;
+ if(!(LimitSw::IsPressed(RIGHTlim))) {
+
+ //超音波
+ if(Ult_right>0) {
+ if(Ult_right<15) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25+(15-Ult_right);
+ motor[TIRE_BL].pwm=25+(15-Ult_right);
+ motor[TIRE_BR].pwm=25;
+ } else if(Ult_right>=15) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=25+(Ult_right-15);
+ motor[TIRE_FR].pwm=25;
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25+(Ult_right-15);
+ }
+ } else {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25;
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25;
+ }
+
+ /*
+ if((Ult_left>0)&&(Ult_right>0)) {//データを受け取っているとき
+ if( (Ult_left+Ult_right)<=25||(Ult_left+Ult_right)>=35) {
+ if(((Ult_left-Ult_right)>=5)||((Ult_left-Ult_right)<=-5)) {
+ if(Ult_left-Ult_right<=0) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+
+ motor[TIRE_BL].pwm=25+(-1*(Ult_left-Ult_right));
+ motor[TIRE_BR].pwm=25+(-1*(Ult_left-Ult_right));
+
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25;
+ } else if(Ult_left-Ult_right>0) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_FR].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25;
+ }
+ } else if((Ult_left+Ult_right)<=25) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=25;
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=0;
+ } else if((Ult_left+Ult_right)>=35) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=25;
+ }
+ } else {
+ if(Ult_left-Ult_right<=0) {
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+
+ motor[TIRE_BL].pwm=25+(-1*(Ult_left-Ult_right));
+ motor[TIRE_BR].pwm=25+(-1*(Ult_left-Ult_right));
+
+ motor[TIRE_FL].pwm=25;
+ motor[TIRE_FR].pwm=25;
+
+ } else if(Ult_left-Ult_right>0) {
+ motor[TIRE_FL].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_FR].pwm=25+(1*(Ult_left-Ult_right));
+ motor[TIRE_BL].pwm=25;
+ motor[TIRE_BR].pwm=25;
+ }
+ }
+ } else {
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+
+ }
+ */
+ } else {
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ phase=5;
+ }
+ } else if(phase==5) {
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=30;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=30;
+ //斜め後ろに下がる
+ } else if(phase==10) {
+ if((Ult_left>0)&&(Ult_right>0)) {//データを受け取っているとき
+ if((Ult_left<16)&&(Ult_left>14)&&(Ult_right<16)&&(Ult_right>14)) { //合った場合
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=255;
+ motor[TIRE_FR].pwm=255;
+ motor[TIRE_BL].pwm=255;
+ motor[TIRE_BR].pwm=255;
+ phase=3;//system phase increasing
+ } else if((Ult_left<16)&&(Ult_left>14)) { //Ult_leftのみあった場合
+ if(Ult_right>16) { //Ult_rightが遠い場合
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=13;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=13;
+ } else if(Ult_right<14) { //Ult_rightが近い場合
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=0;
+ motor[TIRE_FR].pwm=13;
+ motor[TIRE_BL].pwm=0;
+ motor[TIRE_BR].pwm=13;
+ }
+ } else if((Ult_right<16)&&(Ult_right>14)) { //Ult_rightのみあった場合
+ if(Ult_left>16) { //Ult_leftが遠い場合
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=13;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=13;
+ motor[TIRE_BR].pwm=0;
+ } else if(Ult_left<14) { //Ult_leftが近い場合
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=13;
+ motor[TIRE_FR].pwm=0;
+ motor[TIRE_BL].pwm=13;
+ motor[TIRE_BR].pwm=0;
+ }
+ } else { //どっちもあってない場合
+ if( (Ult_left+Ult_right)<=25||(Ult_left+Ult_right)>=35) {//離れすぎているor近すぎるとき
+ if((Ult_left-Ult_right)>0||((Ult_left-Ult_right)<0) ) { //傾きが大きいとき
+ if((Ult_left-Ult_right)>0) { //Ult_leftの方が後ろに来ているとき
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_FR].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BR].pwm=10*Ult_left-Ult_right;
+ } else if((Ult_left-Ult_right)<=0) { //Ult_rightの方が後ろに来ているとき
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_FR].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BR].pwm=10*Ult_left-Ult_right;
+ }
+ }
+ } else { //さほど離れてはいないが傾きが大きいとき
+ if((Ult_left-Ult_right)>0) { //Ult_leftの方が後ろに来ているとき
+ motor[TIRE_FL].dir=FOR;
+ motor[TIRE_FR].dir=FOR;
+ motor[TIRE_BL].dir=FOR;
+ motor[TIRE_BR].dir=FOR;
+ motor[TIRE_FL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_FR].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BR].pwm=10*Ult_left-Ult_right;
+ } else if((Ult_left-Ult_right)<=0) { //Ult_rightの方が後ろに来ているとき
+ motor[TIRE_FL].dir=BACK;
+ motor[TIRE_FR].dir=BACK;
+ motor[TIRE_BL].dir=BACK;
+ motor[TIRE_BR].dir=BACK;
+ motor[TIRE_FL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_FR].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BL].pwm=10*Ult_left-Ult_right;
+ motor[TIRE_BR].pwm=10*Ult_left-Ult_right;
+ }
+ }
+ }
+
+ } else {//データを受け取ってないとき
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ }
+ } else {
+ //一応
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ }
+ } else {
+ motor[TIRE_FL].dir=BRAKE;
+ motor[TIRE_FR].dir=BRAKE;
+ motor[TIRE_BL].dir=BRAKE;
+ motor[TIRE_BR].dir=BRAKE;
+ motor[TIRE_FL].pwm=100;
+ motor[TIRE_FR].pwm=100;
+ motor[TIRE_BL].pwm=100;
+ motor[TIRE_BR].pwm=100;
+ }
}
#endif
#if USE_PROCESS_NUM>3
-static void Process3()
+static void Process3()
{
- AllActuatorReset();
- lineFase = 0;
+ AllActuatorReset();
+ lineFase = 0;
}
#endif
#if USE_PROCESS_NUM>4
-static void Process4()
+static void Process4()
{
-
- static int x,y;
- static int count = 0;
-
- linePara_U = lineCast(LineHub::GetPara(0));
- linePara_B = lineCast(LineHub::GetPara(2));
- linePara_L = lineCast(LineHub::GetPara(3));
- linePara_R = lineCast(LineHub::GetPara(4));
-
- if(linePara_B == 'A' && count == 0) {
- lineFase = 1;
- }
+
+ static int x,y;
+ static int count = 0;
+
+ linePara_U = lineCast(LineHub::GetPara(0));
+ linePara_B = lineCast(LineHub::GetPara(2));
+ linePara_L = lineCast(LineHub::GetPara(3));
+ linePara_R = lineCast(LineHub::GetPara(4));
+
+ if(linePara_B == 'A' && count == 0) {
+ lineFase = 1;
+ }
- if(lineFase == 0) {
- pw = 0.5;
- switch(linePara_U) {
- case -2:
- x = 5;
- y = 3;
- break;
- case -3:
- x = 5;
- y = 3;
- break;
- case -1:
- x = 6;
- y = 3;
- break;
- case 0:
- x = 7;
- y = 3;
- break;
- case 1:
- x = 8;
- y = 3;
- break;
- case 3:
- x = 9;
- y = 3;
- break;
- case 2:
- x = 9;
- y = 3;
- break;
- case 'A':
- lineCheck = true;
- x = x;
- y = y;
- break;
- case 'N':
- x = 7;
- y = 7;
- break;
- x = 7;
- y = 7;
- default:
- x = 9;
- y = 9;
- }
- if(lineCheck == true && (!(linePara_U) == 'A')) {
- count++;
- }
- } else if(lineFase == 1) {
- pw = 0.3;
- x = 7;
- y = 9;
- if(linePara_R == 0) {
- lineFase = 2;
- x = 7;
- y = 7;
- }
- } else if(lineFase == 2) {
- x = 7;
- y = 7;
- } else {
- x = 7;
- y = 7;
- }
-
- int t = 0;
- if((linePara_U + linePara_B) > 3) t = 1;
-
- if(controller->Button.A) {
- motor[TIRE_BL].dir = SetStatus(-omni[y][14-x] );
- motor[TIRE_FL].dir = SetStatus(omni[y][x]);
- motor[TIRE_BR].dir = SetStatus(-omni[14-x][14-y]);
- motor[TIRE_FR].dir = SetStatus(omni[x][14-y]);
-
- motor[TIRE_FR].pwm = SetPWM((omni[y][14-x])) * pw;
- motor[TIRE_FL].pwm = SetPWM((omni[y][x])) * pw;
- motor[TIRE_BR].pwm = SetPWM((omni[14-x][14-y])) * pw;
- motor[TIRE_BL].pwm = SetPWM((omni[x][14-y])) * pw;
- } else {
- motor[TIRE_BL].dir = SetStatus(0);
- motor[TIRE_FL].dir = SetStatus(0);
- motor[TIRE_BR].dir = SetStatus(0);
- motor[TIRE_FR].dir = SetStatus(0);
-
- motor[TIRE_FR].pwm = SetPWM(0);
- motor[TIRE_FL].pwm = SetPWM(0);
- motor[TIRE_BR].pwm = SetPWM(0);
- motor[TIRE_BL].pwm = SetPWM(0);
- }
-
+ if(lineFase == 0) {
+ pw = 0.5;
+ switch(linePara_U) {
+ case -2:
+ x = 5;
+ y = 3;
+ break;
+ case -3:
+ x = 5;
+ y = 3;
+ break;
+ case -1:
+ x = 6;
+ y = 3;
+ break;
+ case 0:
+ x = 7;
+ y = 3;
+ break;
+ case 1:
+ x = 8;
+ y = 3;
+ break;
+ case 3:
+ x = 9;
+ y = 3;
+ break;
+ case 2:
+ x = 9;
+ y = 3;
+ break;
+ case 'A':
+ lineCheck = true;
+ x = x;
+ y = y;
+ break;
+ case 'N':
+ x = 7;
+ y = 7;
+ break;
+ x = 7;
+ y = 7;
+ default:
+ x = 9;
+ y = 9;
+ }
+ if(lineCheck == true && (!(linePara_U) == 'A')) {
+ count++;
+ }
+ } else if(lineFase == 1) {
+ pw = 0.3;
+ x = 7;
+ y = 9;
+ if(linePara_R == 0) {
+ lineFase = 2;
+ x = 7;
+ y = 7;
+ }
+ } else if(lineFase == 2) {
+ x = 7;
+ y = 7;
+ } else {
+ x = 7;
+ y = 7;
+ }
+
+ int t = 0;
+ if((linePara_U + linePara_B) > 3) t = 1;
+
+ if(controller->Button.A) {
+ motor[TIRE_BL].dir = SetStatus(-omni[y][14-x] );
+ motor[TIRE_FL].dir = SetStatus(omni[y][x]);
+ motor[TIRE_BR].dir = SetStatus(-omni[14-x][14-y]);
+ motor[TIRE_FR].dir = SetStatus(omni[x][14-y]);
+
+ motor[TIRE_FR].pwm = SetPWM((omni[y][14-x])) * pw;
+ motor[TIRE_FL].pwm = SetPWM((omni[y][x])) * pw;
+ motor[TIRE_BR].pwm = SetPWM((omni[14-x][14-y])) * pw;
+ motor[TIRE_BL].pwm = SetPWM((omni[x][14-y])) * pw;
+ } else {
+ motor[TIRE_BL].dir = SetStatus(0);
+ motor[TIRE_FL].dir = SetStatus(0);
+ motor[TIRE_BR].dir = SetStatus(0);
+ motor[TIRE_FR].dir = SetStatus(0);
+
+ motor[TIRE_FR].pwm = SetPWM(0);
+ motor[TIRE_FL].pwm = SetPWM(0);
+ motor[TIRE_BR].pwm = SetPWM(0);
+ motor[TIRE_BL].pwm = SetPWM(0);
+ }
+
}
#endif
#if USE_PROCESS_NUM>5
-static void Process5()
-{
- lineFase = 0;
- lineCheck = true;
+static void Process5()
+{
+ lineFase = 0;
+ lineCheck = true;
}
#endif
#if USE_PROCESS_NUM>6
-static void Process6()
+static void Process6()
{
-
- for(int i = 0; i < 8; i++){
- linePara[i] = lineCast(LineHub::GetPara(i));
- }
-
- static int count = 100000;
- count++;
-
- if(count < 10000) {
- lineCheck = false;
- } else {
- lineCheck = true;
- }
-
- if(lineFase == 0) { // 前進
- switch(linePara[0]) {
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BRAKE;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = BRAKE;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 0;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 0;
- break;
- case -3:
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BACK;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = FOR;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 10;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 10;
- break;
- case -1:
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BACK;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = FOR;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 20;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 20;
- break;
- case 0:
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BACK;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = FOR;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 30;
- break;
- case 1:
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BACK;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = FOR;
- motor[TIRE_FL].pwm = 20;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 20;
- motor[TIRE_BL].pwm = 30;
- break;
- case 3:
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = FOR;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = BACK;
- motor[TIRE_FL].pwm = 10;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 10;
- motor[TIRE_BL].pwm = 30;
- break;
- case 2:
- motor[TIRE_FL].dir = BRAKE;
- motor[TIRE_BL].dir = FOR;
- motor[TIRE_BR].dir = BRAKE;
- motor[TIRE_FR].dir = BACK;
- motor[TIRE_FL].pwm = 0;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 0;
- motor[TIRE_BL].pwm = 30;
- break;
- case 'A':
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = BACK;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = FOR;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 30;
- if(lineCheck == true) {
- lineCount++;
- count = 0;
- }
- default:
- motor[TIRE_FL].dir = BRAKE;
- motor[TIRE_BL].dir = BRAKE;
- motor[TIRE_BR].dir = BRAKE;
- motor[TIRE_FR].dir = BRAKE;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 30;
- }
- if(lineCount == 1) {
- lineFase = 1;
- }
- } else if(lineFase == 1) { // 前進 低速
- motor[TIRE_FL].dir = FOR;
- motor[TIRE_BL].dir = FOR;
- motor[TIRE_BR].dir = BACK;
- motor[TIRE_FR].dir = BACK;
- motor[TIRE_FL].pwm = 15;
- motor[TIRE_FR].pwm = 15;
- motor[TIRE_BR].pwm = 15;
- motor[TIRE_BL].pwm = 15;
- if(linePara[4] == 0) {
- lineFase = 2;
- motor[TIRE_FL].dir = BRAKE;
- motor[TIRE_BL].dir = BRAKE;
- motor[TIRE_BR].dir = BRAKE;
- motor[TIRE_FR].dir = BRAKE;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 30;
- }
- } else if(lineFase == 2){ // 位置調整
- lineFase = 3;
- } else if(lineFase == 3){ // 右 直進
- motor[TIRE_FL].dir = BRAKE;
- motor[TIRE_BL].dir = BRAKE;
- motor[TIRE_BR].dir = BRAKE;
- motor[TIRE_FR].dir = BRAKE;
- motor[TIRE_FL].pwm = 30;
- motor[TIRE_FR].pwm = 30;
- motor[TIRE_BR].pwm = 30;
- motor[TIRE_BL].pwm = 30;
- }
-
+
+ for(int i = 0; i < 8; i++) {
+ linePara[i] = lineCast(LineHub::GetPara(i));
+ }
+
+ static int count = 100000;
+ count++;
+
+ if(count < 10000) {
+ lineCheck = false;
+ } else {
+ lineCheck = true;
+ }
+
+ if(lineFase == 0) { // 前進
+ switch(linePara[0]) {
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BRAKE;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = BRAKE;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 0;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 0;
+ break;
+ case -3:
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BACK;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 10;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 10;
+ break;
+ case -1:
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BACK;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 20;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 20;
+ break;
+ case 0:
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BACK;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 30;
+ break;
+ case 1:
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BACK;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = 20;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 20;
+ motor[TIRE_BL].pwm = 30;
+ break;
+ case 3:
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = FOR;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = BACK;
+ motor[TIRE_FL].pwm = 10;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 10;
+ motor[TIRE_BL].pwm = 30;
+ break;
+ case 2:
+ motor[TIRE_FL].dir = BRAKE;
+ motor[TIRE_BL].dir = FOR;
+ motor[TIRE_BR].dir = BRAKE;
+ motor[TIRE_FR].dir = BACK;
+ motor[TIRE_FL].pwm = 0;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 0;
+ motor[TIRE_BL].pwm = 30;
+ break;
+ case 'A':
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = BACK;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 30;
+ if(lineCheck == true) {
+ lineCount++;
+ count = 0;
+ }
+ default:
+ motor[TIRE_FL].dir = BRAKE;
+ motor[TIRE_BL].dir = BRAKE;
+ motor[TIRE_BR].dir = BRAKE;
+ motor[TIRE_FR].dir = BRAKE;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 30;
+ }
+ if(lineCount == 1) {
+ lineFase = 1;
+ }
+ } else if(lineFase == 1) { // 前進 低速
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = FOR;
+ motor[TIRE_BR].dir = BACK;
+ motor[TIRE_FR].dir = BACK;
+ motor[TIRE_FL].pwm = 15;
+ motor[TIRE_FR].pwm = 15;
+ motor[TIRE_BR].pwm = 15;
+ motor[TIRE_BL].pwm = 15;
+ if(linePara[4] == 0) {
+ lineFase = 2;
+ motor[TIRE_FL].dir = BRAKE;
+ motor[TIRE_BL].dir = BRAKE;
+ motor[TIRE_BR].dir = BRAKE;
+ motor[TIRE_FR].dir = BRAKE;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 30;
+ }
+ } else if(lineFase == 2) { // 位置調整
+ lineFase = 3;
+ } else if(lineFase == 3) { // 右 直進
+ motor[TIRE_FL].dir = BRAKE;
+ motor[TIRE_BL].dir = BRAKE;
+ motor[TIRE_BR].dir = BRAKE;
+ motor[TIRE_FR].dir = BRAKE;
+ motor[TIRE_FL].pwm = 30;
+ motor[TIRE_FR].pwm = 30;
+ motor[TIRE_BR].pwm = 30;
+ motor[TIRE_BL].pwm = 30;
+ }
+
+}
+#endif
+Timer samp;
+#if USE_PROCESS_NUM>7
+static void Process7()
+{
+ ;
+ static int flag=0;
+ static int FL_PWM=0;
+ static int FR_PWM=0;
+ static int BL_PWM=0;
+ static int BR_PWM=0;
+ int targetpulse=1000;
+
+ if(flag==0) {
+
+ samp.start();
+
+ flag=1;
+ } else {
+ int pulseFL = -encoder[FL].getPulses()/samp.read();
+ int pulseBL = -encoder[BL].getPulses()/samp.read();
+ int pulseBR = -encoder[BR].getPulses()/samp.read();
+ int pulseFR = -encoder[FR].getPulses()/samp.read();
+ pc.printf("%f ,pulseFL:%d\r\n",samp.read(),pulseFL);
+
+ FL_PWM=FL_PWM+=0.01*(targetpulse-pulseFL);
+ FR_PWM=FR_PWM+=0.01*(targetpulse-pulseFR);
+ BL_PWM=BL_PWM+=0.01*(targetpulse-pulseBL);
+ BR_PWM=BR_PWM+=0.01*(targetpulse-pulseBR);
+ motor[TIRE_FL].dir = FOR;
+ motor[TIRE_BL].dir = FOR;
+ motor[TIRE_BR].dir = FOR;
+ motor[TIRE_FR].dir = FOR;
+ motor[TIRE_FL].pwm = FL_PWM;
+ motor[TIRE_FR].pwm = FR_PWM;
+ motor[TIRE_BR].pwm = BR_PWM;
+ motor[TIRE_BL].pwm = BL_PWM;
+ }
}
#endif
-#if USE_PROCESS_NUM>7
-static void Process7()
-{
-
-}
-#endif
-
-#if USE_PROCESS_NUM>8
+#if USE_PROCESS_NUM>8
static void Process8()
{
- if(controller->Button.A) {
- rotaconSampling.start();
- PIDflag = true;
-
- //linePara_U = LineHub::GetPara(0);
- //linePara_B = LineHub::GetPara(3);
-
-
- pulsePV[FL] = encoder[FL].getPulses();
- pulsePV[BL] = encoder[BL].getPulses();
- pulsePV[BR] = encoder[BR].getPulses();
- pulsePV[FR] = encoder[FR].getPulses();
-
-
- for (int i = 0; i < 4; i++) {
- timeCV[i] = timePV[i];
- timePV[i] = rotaconSampling.read();
- tireProcessRPM[i] = (pulsePV[i] - pulseCV[i])/ (float)(256 * 2) / (timePV[i] - timeCV[i]) * 60;
- pulseCV[i] = pulsePV[i];
- }
-
- move.Vx = 0.5;
- move.Vy = 0.5;
- move.Va = 0;
-
- correction_LT.Vx = 0; //0.1 * linePara_U;
- correction_LT.Vy = 0;
- correction_LT.Va = 0;
-
- synthetic.Vx = move.Vx + correction_LT.Vx;
- synthetic.Vy = move.Vy + correction_LT.Vy;
- synthetic.Va = move.Va + correction_LT.Va;
-
- sita = 0;
-
- //タイヤの目標速度算出
- float sinR = 0.7071 * (float)sin(sita);
- float cosR = 0.7071 * (float)cos(sita);
- float nv = (60 * 1000) / ( 2.00 * PI * tireR);
- tireTargetRPM[FL] = ((+ synthetic.Vx * (sinR - cosR)) - (synthetic.Vy * (sinR + cosR)) + (ucR * synthetic.Va)) * nv;
- tireTargetRPM[BL] = ((+ synthetic.Vx * (sinR + cosR)) + (synthetic.Vy * (sinR - cosR)) + (ucR * synthetic.Va)) * nv;
- tireTargetRPM[BR] = ((- synthetic.Vx * (sinR - cosR)) + (synthetic.Vy * (sinR + cosR)) + (ucR * synthetic.Va)) * nv;
- tireTargetRPM[FR] = ((- synthetic.Vx * (sinR + cosR)) - (synthetic.Vy * (sinR - cosR)) + (ucR * synthetic.Va)) * nv;
-
- //pc.printf("process : %f target : %f\n\r",tireProcessRPM[0],tireTargetRPM[0]);
-
- //PIDによるPWM算出
-
- //モータの駆動
- for (int i = 0; i < 4; i++) {
- if (tirePWM[i] > 255){
- tirePWM[i] = 255;
- } else if (tirePWM[i] < -255) {
- tirePWM[i] = -255;
- }
- }
-
- for(int i = 0;i < 4;i++){
- motor[i].dir = SetStatus(tirePWM[i]);
- motor[i].pwm = SetPWM(tirePWM[i]);
- }
- } else {
- PIDflag = false;
- rotaconSampling.stop();
- rotaconSampling.reset();
- for(int i = 0;i < 4;i++){
- encoder[i].reset();
- pulsePV[i] = 0;
- pulseCV[i] = 0;
- timePV[i] = 0;
- timeCV[i] = 0;
- tirePWM[i] = 0;
- motor[i].dir = SetStatus(tirePWM[i]);
- motor[i].pwm = SetPWM(tirePWM[i]);
- }
- }
+ if(controller->Button.A) {
+ rotaconSampling.start();
+ PIDflag = true;
+
+ //linePara_U = LineHub::GetPara(0);
+ //linePara_B = LineHub::GetPara(3);
+
+
+ pulsePV[FL] = encoder[FL].getPulses();
+ pulsePV[BL] = encoder[BL].getPulses();
+ pulsePV[BR] = encoder[BR].getPulses();
+ pulsePV[FR] = encoder[FR].getPulses();
+
+
+ for (int i = 0; i < 4; i++) {
+ timeCV[i] = timePV[i];
+ timePV[i] = rotaconSampling.read();
+ tireProcessRPM[i] = (pulsePV[i] - pulseCV[i])/ (float)(256 * 2) / (timePV[i] - timeCV[i]) * 60;
+ pulseCV[i] = pulsePV[i];
+ }
+
+ move.Vx = 0.5;
+ move.Vy = 0.5;
+ move.Va = 0;
+
+ correction_LT.Vx = 0; //0.1 * linePara_U;
+ correction_LT.Vy = 0;
+ correction_LT.Va = 0;
+
+ synthetic.Vx = move.Vx + correction_LT.Vx;
+ synthetic.Vy = move.Vy + correction_LT.Vy;
+ synthetic.Va = move.Va + correction_LT.Va;
+
+ sita = 0;
+
+ //タイヤの目標速度算出
+ float sinR = 0.7071f * (float)sin(sita);
+ float cosR = 0.7071f * (float)cos(sita);
+ float nv = (60 * 1000) / ( 2.00 * PI * tireR);
+ tireTargetRPM[FL] = ((+ synthetic.Vx * (sinR - cosR)) - (synthetic.Vy * (sinR + cosR)) + (ucR * synthetic.Va)) * nv;
+ tireTargetRPM[BL] = ((+ synthetic.Vx * (sinR + cosR)) + (synthetic.Vy * (sinR - cosR)) + (ucR * synthetic.Va)) * nv;
+ tireTargetRPM[BR] = ((- synthetic.Vx * (sinR - cosR)) + (synthetic.Vy * (sinR + cosR)) + (ucR * synthetic.Va)) * nv;
+ tireTargetRPM[FR] = ((- synthetic.Vx * (sinR + cosR)) - (synthetic.Vy * (sinR - cosR)) + (ucR * synthetic.Va)) * nv;
+
+ //pc.printf("process : %f target : %f\n\r",tireProcessRPM[0],tireTargetRPM[0]);
+
+ //PIDによるPWM算出
+
+ //モータの駆動
+ for (int i = 0; i < 4; i++) {
+ if (tirePWM[i] > 255) {
+ tirePWM[i] = 255;
+ } else if (tirePWM[i] < -255) {
+ tirePWM[i] = -255;
+ }
+ }
+
+ for(int i = 0; i < 4; i++) {
+ motor[i].dir = SetStatus(tirePWM[i]);
+ motor[i].pwm = SetPWM(tirePWM[i]);
+ }
+ } else {
+ PIDflag = false;
+ rotaconSampling.stop();
+ rotaconSampling.reset();
+ for(int i = 0; i < 4; i++) {
+ encoder[i].reset();
+ pulsePV[i] = 0;
+ pulseCV[i] = 0;
+ timePV[i] = 0;
+ timeCV[i] = 0;
+ tirePWM[i] = 0;
+ motor[i].dir = SetStatus(tirePWM[i]);
+ motor[i].pwm = SetPWM(tirePWM[i]);
+ }
+ }
}
#endif
#if USE_PROCESS_NUM>9
static void Process9()
{
-
+
}
#endif
#endif
@@ -878,60 +1495,63 @@
static void AllActuatorReset()
{
- #ifdef USE_SOLENOID
- solenoid.all = ALL_SOLENOID_OFF;
- #endif
+#ifdef USE_SOLENOID
+ solenoid.all = ALL_SOLENOID_OFF;
+#endif
- #ifdef USE_MOTOR
- for (uint8_t i = 0; i < MOUNTING_MOTOR_NUM; i++)
- {
- motor[i].dir = FREE;
- motor[i].pwm = 0;
- }
- #endif
+#ifdef USE_MOTOR
+ for (uint8_t i = 0; i < MOUNTING_MOTOR_NUM; i++) {
+ motor[i].dir = FREE;
+ motor[i].pwm = 0;
+ }
+#endif
}
-void BuzzerTimer_func(){
+void BuzzerTimer_func()
+{
buzzer = !buzzer;
//LED_DEBUG0 = !LED_DEBUG0;
}
-void TapeLedEms_func() {
+void TapeLedEms_func()
+{
sendLedData.code = sendLedData.code == (uint32_t)Red ? (uint32_t)Black : (uint32_t)Red;
}
#pragma region USER-DEFINED-FUNCTIONS
-void tirePID() {
- if(PIDflag == true) {
- //加算するPID値の算出
- rotaconPID[0].SetPV(tireProcessRPM[FL],tireTargetRPM[FL]);
- rotaconPID[1].SetPV(tireProcessRPM[BL],tireTargetRPM[BL]);
- rotaconPID[2].SetPV(tireProcessRPM[FR],tireTargetRPM[FR]);
- rotaconPID[3].SetPV(tireProcessRPM[BR],tireTargetRPM[BR]);
- //PID値の加算
- tirePWM[FL] += rotaconPID[0].GetMV();
- tirePWM[BL] += rotaconPID[1].GetMV();
- tirePWM[FR] += rotaconPID[2].GetMV();
- tirePWM[BR] += rotaconPID[3].GetMV();
- }
+void tirePID()
+{
+ if(PIDflag == true) {
+ //加算するPID値の算出
+ rotaconPID[0].SetPV(tireProcessRPM[FL],tireTargetRPM[FL]);
+ rotaconPID[1].SetPV(tireProcessRPM[BL],tireTargetRPM[BL]);
+ rotaconPID[2].SetPV(tireProcessRPM[FR],tireTargetRPM[FR]);
+ rotaconPID[3].SetPV(tireProcessRPM[BR],tireTargetRPM[BR]);
+ //PID値の加算
+ tirePWM[FL] += rotaconPID[0].GetMV();
+ tirePWM[BL] += rotaconPID[1].GetMV();
+ tirePWM[FR] += rotaconPID[2].GetMV();
+ tirePWM[BR] += rotaconPID[3].GetMV();
+ }
}
-int lineCast(char k) {
- int l;
- switch(k) {
- case 255:
- l = -1;
- break;
- case 254:
- l = -2;
- break;
- case 253:
- l = -3;
- break;
- default:
- l = k;
- }
- return l;
+int lineCast(char k)
+{
+ int l;
+ switch(k) {
+ case 255:
+ l = -1;
+ break;
+ case 254:
+ l = -2;
+ break;
+ case 253:
+ l = -3;
+ break;
+ default:
+ l = k;
+ }
+ return l;
}
#pragma endregion
--- a/System/Process/Process.h Wed Sep 18 02:03:56 2019 +0000 +++ b/System/Process/Process.h Fri Sep 27 05:19:58 2019 +0000 @@ -10,8 +10,8 @@ void SystemProcess(); #define TIRE_FL 0 -#define TIRE_FR 1 -#define TIRE_BL 3 +#define TIRE_FR 3 +#define TIRE_BL 1 #define TIRE_BR 2 #define LIFT_LB 4 @@ -21,11 +21,35 @@ #define LSW_LB 0 #define LSW_RB 1 - - +#define ECHO_0 PC_3 +#define ECHO_1 PC_1 + +#define TRIG_0 PC_0 +#define TRIG_1 PB_0 + +#define TEMP PC_2 +#define RED 0 +#define BLUE 1 +//4~7は使っています +//#define CLOTHESPIN solenoid.solenoid2 +#define RED_OR_BLUE 8 +#define STARTSW 15 +#define LEFTlim 1 +#define RIGHTlim 2 +#define SELECT_1 PB_8//LS18 +#define SELECT_2 PC_9//LS19 +#define SELECT_3 PC_8//LS20 +/* +#define ECHO_0 D4 +#define ECHO_1 PC_1 + +#define TRIG_0 D5 +#define TRIG_1 PB_0 + +#define TEMP PC_2 - +*/ typedef union