将 double 替换为 float 以提高性能
This commit is contained in:
parent
2efd7a390b
commit
1d9c7466b4
@ -87,13 +87,13 @@ uint8_t CalcDirection(void);
|
|||||||
#define CATCH_END 2
|
#define CATCH_END 2
|
||||||
#define RELEASE_END 3
|
#define RELEASE_END 3
|
||||||
//沿线直行,在触发条件后停止
|
//沿线直行,在触发条件后停止
|
||||||
void LineForward(uint8_t end_position, double speed_rate = 1.0);
|
void LineForward(uint8_t end_position, float speed_rate = 1.0);
|
||||||
|
|
||||||
//沿线后退,在触发条件后停止
|
//沿线后退,在触发条件后停止
|
||||||
void LineBackward(uint8_t end_position, double speed_rate = 1.0);
|
void LineBackward(uint8_t end_position, float speed_rate = 1.0);
|
||||||
|
|
||||||
//直行或后退或转向
|
//直行或后退或转向
|
||||||
void TurnDirection(uint8_t direction, double speed_rate = 1.0);
|
void TurnDirection(uint8_t direction, float speed_rate = 1.0);
|
||||||
//***************************************************************************************
|
//***************************************************************************************
|
||||||
|
|
||||||
|
|
||||||
@ -280,7 +280,7 @@ uint8_t CalcDirection(void)
|
|||||||
|
|
||||||
|
|
||||||
//沿线直行,在触发条件后停止
|
//沿线直行,在触发条件后停止
|
||||||
void LineForward(uint8_t end_position, double speed_rate)
|
void LineForward(uint8_t end_position, float speed_rate)
|
||||||
{
|
{
|
||||||
//记录开始时间
|
//记录开始时间
|
||||||
unsigned long begin_time = micros();
|
unsigned long begin_time = micros();
|
||||||
@ -329,7 +329,7 @@ void LineForward(uint8_t end_position, double speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//沿线后退,在触发条件后停止
|
//沿线后退,在触发条件后停止
|
||||||
void LineBackward(uint8_t end_position, double speed_rate)
|
void LineBackward(uint8_t end_position, float speed_rate)
|
||||||
{
|
{
|
||||||
while(1)
|
while(1)
|
||||||
{
|
{
|
||||||
@ -366,7 +366,7 @@ void LineBackward(uint8_t end_position, double speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//直行或后退或转向
|
//直行或后退或转向
|
||||||
void TurnDirection(uint8_t direction, double speed_rate)
|
void TurnDirection(uint8_t direction, float speed_rate)
|
||||||
{
|
{
|
||||||
if (direction == FORWARD) //继续直行
|
if (direction == FORWARD) //继续直行
|
||||||
{
|
{
|
||||||
|
|||||||
@ -11,7 +11,7 @@ Move::Move()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
Move::Move(double global_speed_rate)
|
Move::Move(float global_speed_rate)
|
||||||
{
|
{
|
||||||
Move();
|
Move();
|
||||||
|
|
||||||
@ -20,7 +20,7 @@ Move::Move(double global_speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//设置全局速度比率
|
//设置全局速度比率
|
||||||
void Move::SetGlobalSpeedRate(double global_speed_rate)
|
void Move::SetGlobalSpeedRate(float global_speed_rate)
|
||||||
{
|
{
|
||||||
this->global_speed_rate = global_speed_rate;
|
this->global_speed_rate = global_speed_rate;
|
||||||
}
|
}
|
||||||
@ -34,14 +34,14 @@ uint8_t Move::GetCurrentMove(void)
|
|||||||
|
|
||||||
|
|
||||||
//获取当前运动速度比率
|
//获取当前运动速度比率
|
||||||
double Move::GetCurrentSpeedRate(void)
|
float Move::GetCurrentSpeedRate(void)
|
||||||
{
|
{
|
||||||
return current_speed_rate;
|
return current_speed_rate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//控制某个轮子转动
|
//控制某个轮子转动
|
||||||
void Move::Wheel(uint8_t wheel, uint8_t rotation, double speed_rate)
|
void Move::Wheel(uint8_t wheel, uint8_t rotation, float speed_rate)
|
||||||
{
|
{
|
||||||
uint8_t pin_in1, pin_in2, pin_ena;
|
uint8_t pin_in1, pin_in2, pin_ena;
|
||||||
|
|
||||||
@ -99,7 +99,7 @@ void Move::Wheel(uint8_t wheel, uint8_t rotation, double speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//前进
|
//前进
|
||||||
void Move::Forward(double speed_rate)
|
void Move::Forward(float speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate);
|
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate);
|
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate);
|
||||||
@ -112,7 +112,7 @@ void Move::Forward(double speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//后退
|
//后退
|
||||||
void Move::Backward(double speed_rate)
|
void Move::Backward(float speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate);
|
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate);
|
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate);
|
||||||
@ -125,7 +125,7 @@ void Move::Backward(double speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//向前左转
|
//向前左转
|
||||||
void Move::ForLeftward(double speed_rate, double turn_speed_rate)
|
void Move::ForLeftward(float speed_rate, float turn_speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate);
|
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate);
|
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, turn_speed_rate * speed_rate);
|
||||||
@ -138,7 +138,7 @@ void Move::ForLeftward(double speed_rate, double turn_speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//向前右转
|
//向前右转
|
||||||
void Move::ForRightward(double speed_rate, double turn_speed_rate)
|
void Move::ForRightward(float speed_rate, float turn_speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate);
|
Wheel(LEFT_A_WHEEL, FORWARD_ROTATION, speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate);
|
Wheel(LEFT_B_WHEEL, FORWARD_ROTATION, speed_rate);
|
||||||
@ -151,7 +151,7 @@ void Move::ForRightward(double speed_rate, double turn_speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//向后左转
|
//向后左转
|
||||||
void Move::BackLeftward(double speed_rate, double turn_speed_rate)
|
void Move::BackLeftward(float speed_rate, float turn_speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate);
|
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate);
|
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, turn_speed_rate * speed_rate);
|
||||||
@ -164,7 +164,7 @@ void Move::BackLeftward(double speed_rate, double turn_speed_rate)
|
|||||||
|
|
||||||
|
|
||||||
//向后右转
|
//向后右转
|
||||||
void Move::BackRightward(double speed_rate, double turn_speed_rate)
|
void Move::BackRightward(float speed_rate, float turn_speed_rate)
|
||||||
{
|
{
|
||||||
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate);
|
Wheel(LEFT_A_WHEEL, BACKWARD_ROTATION, speed_rate);
|
||||||
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate);
|
Wheel(LEFT_B_WHEEL, BACKWARD_ROTATION, speed_rate);
|
||||||
@ -190,7 +190,7 @@ void Move::Stop(void)
|
|||||||
|
|
||||||
|
|
||||||
//向某方向运动
|
//向某方向运动
|
||||||
void Move::MoveDirection(uint8_t direction, double speed_rate, double turn_speed_rate)
|
void Move::MoveDirection(uint8_t direction, float speed_rate, float turn_speed_rate)
|
||||||
{
|
{
|
||||||
switch (direction)
|
switch (direction)
|
||||||
{
|
{
|
||||||
|
|||||||
@ -48,29 +48,29 @@ class Move
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
Move();
|
Move();
|
||||||
Move(double global_speed_rate);
|
Move(float global_speed_rate);
|
||||||
|
|
||||||
void SetGlobalSpeedRate(double global_speed_rate); //设置全局速度比率
|
void SetGlobalSpeedRate(float global_speed_rate); //设置全局速度比率
|
||||||
|
|
||||||
uint8_t GetCurrentMove(void); //获取当前运动方向
|
uint8_t GetCurrentMove(void); //获取当前运动方向
|
||||||
double GetCurrentSpeedRate(void); //获取当前运动速度比率
|
float GetCurrentSpeedRate(void); //获取当前运动速度比率
|
||||||
|
|
||||||
void Wheel(uint8_t wheel, uint8_t rotation, double speed_rate = 1.0); //控制某个轮子转动
|
void Wheel(uint8_t wheel, uint8_t rotation, float speed_rate = 1.0); //控制某个轮子转动
|
||||||
|
|
||||||
void Forward(double speed_rate = 1.0); //前进
|
void Forward(float speed_rate = 1.0); //前进
|
||||||
void Backward(double speed_rate = 1.0); //后退
|
void Backward(float speed_rate = 1.0); //后退
|
||||||
void ForLeftward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前左转
|
void ForLeftward(float speed_rate = 1.0, float turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前左转
|
||||||
void ForRightward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前右转
|
void ForRightward(float speed_rate = 1.0, float turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向前右转
|
||||||
void BackLeftward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后左转
|
void BackLeftward(float speed_rate = 1.0, float turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后左转
|
||||||
void BackRightward(double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后右转
|
void BackRightward(float speed_rate = 1.0, float turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向后右转
|
||||||
void Stop(void); //制动
|
void Stop(void); //制动
|
||||||
|
|
||||||
void MoveDirection(uint8_t direction, double speed_rate = 1.0, double turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向某方向运动
|
void MoveDirection(uint8_t direction, float speed_rate = 1.0, float turn_speed_rate = DEFAULT_TRUN_SPEED_RATE); //向某方向运动
|
||||||
|
|
||||||
private:
|
private:
|
||||||
double global_speed_rate; //全局速度比率
|
float global_speed_rate; //全局速度比率
|
||||||
uint8_t current_move; //当前运动状态
|
uint8_t current_move; //当前运动状态
|
||||||
double current_speed_rate; //当前运动速度比率
|
float current_speed_rate; //当前运动速度比率
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -71,7 +71,7 @@ void Servo::StopActionGroup(void)
|
|||||||
* Return: 无返回
|
* Return: 无返回
|
||||||
* Others:
|
* Others:
|
||||||
*********************************************************************************/
|
*********************************************************************************/
|
||||||
void Servo::SetActionGroupSpeed(uint8_t action_num, double speed)
|
void Servo::SetActionGroupSpeed(uint8_t action_num, float speed)
|
||||||
{
|
{
|
||||||
uint16_t speed_int = (uint16_t)speed;
|
uint16_t speed_int = (uint16_t)speed;
|
||||||
uint8_t buf[7];
|
uint8_t buf[7];
|
||||||
@ -94,14 +94,14 @@ void Servo::SetActionGroupSpeed(uint8_t action_num, double speed)
|
|||||||
* Return: 无返回
|
* Return: 无返回
|
||||||
* Others:
|
* Others:
|
||||||
*********************************************************************************/
|
*********************************************************************************/
|
||||||
void Servo::SetAllActionGroupSpeed(double speed)
|
void Servo::SetAllActionGroupSpeed(float speed)
|
||||||
{
|
{
|
||||||
SetActionGroupSpeed(0xFF, speed); //调用动作组速度设定,组号为0xFF时设置所有组的速度
|
SetActionGroupSpeed(0xFF, speed); //调用动作组速度设定,组号为0xFF时设置所有组的速度
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//恢复初始状态,指定速度
|
//恢复初始状态,指定速度
|
||||||
void Servo::Reset(double speed)
|
void Servo::Reset(float speed)
|
||||||
{
|
{
|
||||||
SetActionGroupSpeed(ACTION_RESET_NUM, speed);
|
SetActionGroupSpeed(ACTION_RESET_NUM, speed);
|
||||||
RunActionGroup(ACTION_RESET_NUM, 1);
|
RunActionGroup(ACTION_RESET_NUM, 1);
|
||||||
@ -110,7 +110,7 @@ void Servo::Reset(double speed)
|
|||||||
|
|
||||||
|
|
||||||
//抓取,指定速度
|
//抓取,指定速度
|
||||||
void Servo::Catch(double speed)
|
void Servo::Catch(float speed)
|
||||||
{
|
{
|
||||||
SetActionGroupSpeed(ACTION_CATCH_NUM, speed);
|
SetActionGroupSpeed(ACTION_CATCH_NUM, speed);
|
||||||
RunActionGroup(ACTION_CATCH_NUM, 1);
|
RunActionGroup(ACTION_CATCH_NUM, 1);
|
||||||
@ -119,7 +119,7 @@ void Servo::Catch(double speed)
|
|||||||
|
|
||||||
|
|
||||||
//释放,指定速度
|
//释放,指定速度
|
||||||
void Servo::Release(double speed)
|
void Servo::Release(float speed)
|
||||||
{
|
{
|
||||||
SetActionGroupSpeed(ACTION_RELEASE_NUM, speed);
|
SetActionGroupSpeed(ACTION_RELEASE_NUM, speed);
|
||||||
RunActionGroup(ACTION_RELEASE_NUM, 1);
|
RunActionGroup(ACTION_RELEASE_NUM, 1);
|
||||||
@ -128,7 +128,7 @@ void Servo::Release(double speed)
|
|||||||
|
|
||||||
|
|
||||||
//停止舵机并恢复初始状态,指定速度
|
//停止舵机并恢复初始状态,指定速度
|
||||||
void Servo::StopAndReset(double speed)
|
void Servo::StopAndReset(float speed)
|
||||||
{
|
{
|
||||||
StopActionGroup();
|
StopActionGroup();
|
||||||
Reset(speed);
|
Reset(speed);
|
||||||
|
|||||||
@ -33,13 +33,13 @@ public:
|
|||||||
|
|
||||||
void RunActionGroup(uint8_t action_num, uint16_t times);
|
void RunActionGroup(uint8_t action_num, uint16_t times);
|
||||||
void StopActionGroup(void);
|
void StopActionGroup(void);
|
||||||
void SetActionGroupSpeed(uint8_t action_num, double speed);
|
void SetActionGroupSpeed(uint8_t action_num, float speed);
|
||||||
void SetAllActionGroupSpeed(double speed);
|
void SetAllActionGroupSpeed(float speed);
|
||||||
|
|
||||||
void Reset(double speed = SERVO_NORMAL_SPEED); //恢复初始状态,指定速度
|
void Reset(float speed = SERVO_NORMAL_SPEED); //恢复初始状态,指定速度
|
||||||
void Catch(double speed = SERVO_NORMAL_SPEED); //抓取,指定速度
|
void Catch(float speed = SERVO_NORMAL_SPEED); //抓取,指定速度
|
||||||
void Release(double speed = SERVO_NORMAL_SPEED); //释放,指定速度
|
void Release(float speed = SERVO_NORMAL_SPEED); //释放,指定速度
|
||||||
void StopAndReset(double speed = SERVO_NORMAL_SPEED); //停止舵机并恢复初始状态,指定速度
|
void StopAndReset(float speed = SERVO_NORMAL_SPEED); //停止舵机并恢复初始状态,指定速度
|
||||||
|
|
||||||
private:
|
private:
|
||||||
HardwareSerial *SerialX;
|
HardwareSerial *SerialX;
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user