From 575b6cefafc3f579bf91cdabe0c3e128afcb369c Mon Sep 17 00:00:00 2001 From: "lxbpxylps@126.com" Date: Sun, 14 Feb 2021 12:40:23 +0800 Subject: [PATCH] =?UTF-8?q?=E6=9B=B4=E6=96=B0=20move=20=E5=BA=93?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- TaiChi/moveTaiChi.cpp | 68 ++++++++++++++++++++++++++----------------- TaiChi/moveTaiChi.h | 40 +++++++++++++------------ 2 files changed, 63 insertions(+), 45 deletions(-) diff --git a/TaiChi/moveTaiChi.cpp b/TaiChi/moveTaiChi.cpp index 82fcd88..4a6afdb 100644 --- a/TaiChi/moveTaiChi.cpp +++ b/TaiChi/moveTaiChi.cpp @@ -7,11 +7,11 @@ Move::Move() { global_speed_rate = DEFAULT_GLOBAL_SPEED_RATE; current_move = STOP; - current_speed_rate = 0; + current_speed_rate = 0.0; } -Move::Move(int global_speed_rate) +Move::Move(double global_speed_rate) { Move(); @@ -20,7 +20,7 @@ Move::Move(int global_speed_rate) //设置全局速度比率 -void Move::SetGlobalSpeedRate(int global_speed_rate) +void Move::SetGlobalSpeedRate(double global_speed_rate) { this->global_speed_rate = global_speed_rate; } @@ -34,14 +34,14 @@ uint8_t Move::GetCurrentMove(void) //获取当前运动速度比率 -int Move::GetCurrentSpeedRate(void) +double Move::GetCurrentSpeedRate(void) { return current_speed_rate; } //控制某个轮子转动 -void Move::Wheel(uint8_t wheel, uint8_t rotation, int speed_rate) +void Move::Wheel(uint8_t wheel, uint8_t rotation, double speed_rate) { uint8_t pin_in1, pin_in2, pin_ena; @@ -83,7 +83,7 @@ void Move::Wheel(uint8_t wheel, uint8_t rotation, int speed_rate) return; //结束函数 } - analogWrite(pin_ena, speed_rate * global_speed_rate * 255.0 / 10000.0); //设置 PWM 波,即转速 + analogWrite(pin_ena, speed_rate * global_speed_rate * 255.0); //设置 PWM 波,即转速 if (rotation == FORWARD_ROTATION) //向前转动 { @@ -99,7 +99,7 @@ void Move::Wheel(uint8_t wheel, uint8_t rotation, int speed_rate) //前进 -void Move::Forward(int speed_rate) +void Move::Forward(double speed_rate) { Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate); Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate); @@ -107,12 +107,12 @@ void Move::Forward(int speed_rate) Wheel(RIGHT_B_WHEEL, FORWARD_ROTATION, speed_rate); current_move = FORWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } //后退 -void Move::Backward(int speed_rate) +void Move::Backward(double speed_rate) { Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate); Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate); @@ -120,59 +120,59 @@ void Move::Backward(int speed_rate) Wheel(RIGHT_B_WHEEL, BACKWARD_ROTATION, speed_rate); current_move = BACKWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } //向前左转 -void Move::ForLeftward(int speed_rate) +void Move::ForLeftward(double speed_rate, double turn_speed_rate) { - Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); - Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); + Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate); + Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate); Wheel(RIGHT_A_WHEEL, FORWARD_ROTATION, speed_rate); Wheel(RIGHT_B_WHEEL, FORWARD_ROTATION, speed_rate); current_move = FORLEFTWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } //向前右转 -void Move::ForRightward(int speed_rate) +void Move::ForRightward(double speed_rate, double turn_speed_rate) { Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate); Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate); - Wheel(RIGHT_A_WHEEL, FORWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); - Wheel(RIGHT_B_WHEEL, FORWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); + Wheel(RIGHT_A_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate); + Wheel(RIGHT_B_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate); current_move = FORRIGHTWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } //向后左转 -void Move::BackLeftward(int speed_rate) +void Move::BackLeftward(double speed_rate, double turn_speed_rate) { - Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); - Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); + Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate); + Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate); Wheel(RIGHT_A_WHEEL, BACKWARD_ROTATION, speed_rate); Wheel(RIGHT_B_WHEEL, BACKWARD_ROTATION, speed_rate); current_move = BACKLEFTWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } //向后右转 -void Move::BackRightward(int speed_rate) +void Move::BackRightward(double speed_rate, double turn_speed_rate) { Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate); Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate); - Wheel(RIGHT_A_WHEEL, BACKWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); - Wheel(RIGHT_B_WHEEL, BACKWARD_ROTATION, TRUN_SPEED_RATE * speed_rate / 100.0); + Wheel(RIGHT_A_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate); + Wheel(RIGHT_B_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate); current_move = BACKRIGHTWARD; - current_speed_rate = speed_rate * global_speed_rate / 100.0; + current_speed_rate = speed_rate; } @@ -186,4 +186,20 @@ void Move::Stop(void) current_move = STOP; current_speed_rate = 0; +} + + +//向某方向运动 +void Move::MoveDirection(uint8_t direction, double speed_rate, double turn_speed_rate) +{ + switch (direction) + { + case FORWARD: Forward(speed_rate); break; + case BACKWARD: Backward(speed_rate); break; + case FORLEFTWARD: ForLeftward(speed_rate, turn_speed_rate); break; + case FORRIGHTWARD: ForRightward(speed_rate, turn_speed_rate); break; + case BACKLEFTWARD: BackLeftward(speed_rate, turn_speed_rate); break; + case BACKRIGHTWARD: BackRightward(speed_rate, turn_speed_rate); break; + case STOP: Stop(); + } } \ No newline at end of file diff --git a/TaiChi/moveTaiChi.h b/TaiChi/moveTaiChi.h index ea4dfcd..4ddc336 100644 --- a/TaiChi/moveTaiChi.h +++ b/TaiChi/moveTaiChi.h @@ -10,22 +10,22 @@ //轮胎旋转方向定义,包括停止 #define FORWARD_ROTATION 0 #define BACKWARD_ROTATION 1 -#define STOP_ROTATION 3 +#define STOP_ROTATION 6 -//运动状态定义 +//运动方向、状态定义,与轮胎旋转方向定义兼容 #define FORWARD 0 #define BACKWARD 1 #define FORLEFTWARD 2 -#define BACKLEFTWARD 3 -#define FORRIGHTWARD 4 +#define FORRIGHTWARD 3 +#define BACKLEFTWARD 4 #define BACKRIGHTWARD 5 #define STOP 6 //默认全局速度比率 -#define DEFAULT_GLOBAL_SPEED_RATE 100 +#define DEFAULT_GLOBAL_SPEED_RATE 1.0 -//转向时一侧减速的比率 -#define TRUN_SPEED_RATE 50 +//默认转向时一侧减速的比率 +#define DEFAULT_TRUN_SPEED_RATE 0.5 //左侧 L298N 接口定义 #define LEFT_L298N_IN1 22 @@ -48,27 +48,29 @@ class Move { public: Move(); - Move(int global_speed_rate); + Move(double global_speed_rate); - void SetGlobalSpeedRate(int global_speed_rate); //设置全局速度比率 + void SetGlobalSpeedRate(double global_speed_rate); //设置全局速度比率 uint8_t GetCurrentMove(void); //获取当前运动方向 - int GetCurrentSpeedRate(void); //获取当前运动速度比率 + double GetCurrentSpeedRate(void); //获取当前运动速度比率 - void Wheel(uint8_t wheel, uint8_t rotation, int speed_rate = 100); //控制某个轮子转动 + void Wheel(uint8_t wheel, uint8_t rotation, double speed_rate = 1.0); //控制某个轮子转动 - void Forward(int speed_rate = 100); //前进 - void Backward(int speed_rate = 100); //后退 - void ForLeftward(int speed_rate = 100); //向前左转 - void ForRightward(int speed_rate = 100); //向前右转 - void BackLeftward(int speed_rate = 100); //向后左转 - void BackRightward(int speed_rate = 100); //向后右转 + void Forward(double speed_rate = 1.0); //前进 + void Backward(double speed_rate = 1.0); //后退 + void ForLeftward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前左转 + void ForRightward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前右转 + void BackLeftward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后左转 + void BackRightward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后右转 void Stop(void); //制动 + void MoveDirection(uint8_t direction, double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向某方向运动 + private: - int global_speed_rate; //全局速度比率 + double global_speed_rate; //全局速度比率 uint8_t current_move; //当前运动状态 - int current_speed_rate; //当前运动速度比率 + double current_speed_rate; //当前运动速度比率 };