完善整机调试功能

This commit is contained in:
lxbpxylps@126.com 2021-02-15 12:28:14 +08:00
parent a487ab4af6
commit 9bd14f85d8
7 changed files with 84 additions and 40 deletions

View File

@ -3,6 +3,10 @@
#include "servoTaiChi.h" //舵机库
//注释以关闭调试功能
#define TAICHI_DEBUG
Move move; //轮胎运动实例
Sensor sensor; //传感器实例
Servo servo; //舵机实例
@ -99,6 +103,10 @@ void TurnDirection(uint8_t direction, float speed_rate = 1.0);
void setup()
{
#ifdef TAICHI_DEBUG
Serial.begin(9600);
#endif
move.Stop();
servo.StopAndReset();
@ -177,7 +185,7 @@ void loop()
//继续后退或转向
TurnDirection(CalcDirection());
}
else move.Stop(); //DEBUG
else move.Stop(); //调试用
//更新标记,继续循环
if (++passed_flag > max_flag)
@ -224,7 +232,7 @@ uint8_t CalcDirection(void)
rx = -ry0;
ry = rx0;
}
else return 254; //DEBUG
else return 254; //调试用
//判断行进方向
if (rx == 0 && ry == 2)
@ -275,13 +283,20 @@ uint8_t CalcDirection(void)
return BACKRIGHTWARD;
}
}
else return 255; //DEBUG
else return 255; //调试用
}
//沿线直行,在触发条件后停止
void LineForward(uint8_t end_position, float speed_rate)
{
#ifdef TAICHI_DEBUG
//调试输出沿线直行状态
Serial.print("#TAICHI: Line Forward");
Serial.print(" end_position: ");
Serial.println((int)end_position);
#endif
//记录开始时间
unsigned long begin_time = micros();
@ -325,12 +340,24 @@ void LineForward(uint8_t end_position, float speed_rate)
break;
}
}
#ifdef TAICHI_DEBUG
//调试输出沿线直行结束
Serial.println("#TAICHI: End Line Forward");
#endif
}
//沿线后退,在触发条件后停止
void LineBackward(uint8_t end_position, float speed_rate)
{
#ifdef TAICHI_DEBUG
//调试输出沿线后退状态
Serial.print("#TAICHI: Line Backward");
Serial.print(" end_position: ");
Serial.println((int)end_position);
#endif
while(1)
{
if (!sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4)) //左侧越线
@ -362,12 +389,24 @@ void LineBackward(uint8_t end_position, float speed_rate)
break;
}
}
#ifdef TAICHI_DEBUG
//调试输出沿线后退结束
Serial.println("#TAICHI: End Line Backward");
#endif
}
//直行或后退或转向
void TurnDirection(uint8_t direction, float speed_rate)
{
#ifdef TAICHI_DEBUG
//调试输出直行或后退或转向状态
Serial.print("#TAICHI: Turn Direction");
Serial.print(" direction: ");
Serial.println((int)direction);
#endif
if (direction == FORWARD) //继续直行
{
//沿线直行,到后端传感器接触线为止
@ -386,4 +425,9 @@ void TurnDirection(uint8_t direction, float speed_rate)
delay(TRUN_CHECK_DELAY); //延时后判断
while(!(sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4))) {}
}
#ifdef TAICHI_DEBUG
//调试输出直行或后退或转向结束
Serial.println("#TAICHI: End Turn Direction");
#endif
}

View File

@ -109,9 +109,9 @@ void Move::Forward(float speed_rate)
current_move = FORWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出前进状态
Serial.print("Move Forward");
Serial.print("#MOVE: Move Forward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -129,9 +129,9 @@ void Move::Backward(float speed_rate)
current_move = BACKWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出后退状态
Serial.print("Move Backward");
Serial.print("#MOVE: Move Backward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -149,9 +149,9 @@ void Move::ForLeftward(float speed_rate, float turn_speed_rate)
current_move = FORLEFTWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出向前左转状态
Serial.print("Move ForLeftward");
Serial.print("#MOVE: Move ForLeftward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -169,9 +169,9 @@ void Move::ForRightward(float speed_rate, float turn_speed_rate)
current_move = FORRIGHTWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出向前右转状态
Serial.print("Move ForRightward");
Serial.print("#MOVE: Move ForRightward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -189,9 +189,9 @@ void Move::BackLeftward(float speed_rate, float turn_speed_rate)
current_move = BACKLEFTWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出向后左转状态
Serial.print("Move BackLeftward");
Serial.print("#MOVE: Move BackLeftward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -209,9 +209,9 @@ void Move::BackRightward(float speed_rate, float turn_speed_rate)
current_move = BACKRIGHTWARD;
current_speed_rate = speed_rate;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出向后右转状态
Serial.print("Move BackRightward");
Serial.print("#MOVE: Move BackRightward");
Serial.print(" speed_rate: ");
Serial.println(speed_rate);
#endif
@ -229,9 +229,9 @@ void Move::Stop(void)
current_move = STOP;
current_speed_rate = 0;
#ifdef DEBUG
#ifdef MOVE_DEBUG
//调试输出制动状态
Serial.print("Move Stop\n");
Serial.println("#MOVE: Move Stop");
#endif
}

View File

@ -3,7 +3,7 @@
//注释以关闭调试功能
#define DEBUG
#define MOVE_DEBUG
//轮胎定义

View File

@ -27,16 +27,16 @@ bool Sensor::IsWhite(uint8_t gray_sensor_num)
gray_val = analogRead(gray_out_pin);
#ifdef DEBUG
#ifdef SENSOR_DEBUG
//调试输出灰度值
switch (gray_sensor_num)
{
case GRAY_1: Serial.print("GRAY_1: "); break;
case GRAY_2: Serial.print("GRAY_2: "); break;
case GRAY_3: Serial.print("GRAY_3: "); break;
case GRAY_4: Serial.print("GRAY_4: "); break;
case GRAY_5: Serial.print("GRAY_5: "); break;
case GRAY_6: Serial.print("GRAY_6: ");
case GRAY_1: Serial.print("#SENSOR: GRAY_1: "); break;
case GRAY_2: Serial.print("#SENSOR: GRAY_2: "); break;
case GRAY_3: Serial.print("#SENSOR: GRAY_3: "); break;
case GRAY_4: Serial.print("#SENSOR: GRAY_4: "); break;
case GRAY_5: Serial.print("#SENSOR: GRAY_5: "); break;
case GRAY_6: Serial.print("#SENSOR: GRAY_6: ");
}
Serial.println(gray_val);
@ -59,15 +59,15 @@ bool Sensor::IsPushed(uint8_t button_num)
button_val = digitalRead(button_out_pin);
#ifdef DEBUG
#ifdef SENSOR_DEBUG
//调试输出按钮状态
if (button_num == BUTTON_1)
Serial.print("BUTTON_1: ");
else Serial.print("BUTTON_2: ");
Serial.print("#SENSOR: BUTTON_1: ");
else Serial.print("#SENSOR: BUTTON_2: ");
if (button_val == LOW)
Serial.print("pushed\n");
else Serial.print("released\n");
Serial.println("pushed");
else Serial.println("released");
#endif
if (button_val == LOW)

View File

@ -3,7 +3,7 @@
//注释以关闭调试功能
#define DEBUG
#define SENSOR_DEBUG
//灰度传感器接口定义

View File

@ -40,9 +40,9 @@ void Servo::RunActionGroup(uint8_t action_num, uint16_t times)
SerialX->write(buf, 7); //发送数据帧
#ifdef DEBUG
#ifdef SERVO_DEBUG
//调试输出动作组执行信息
Serial.print("RunServoActionGroup: ");
Serial.print("#SERVO: RunServoActionGroup: ");
Serial.println((int)action_num);
#endif
}
@ -59,9 +59,9 @@ void Servo::StopActionGroup(void)
SerialX->write(buf, 4); //发送数据帧
#ifdef DEBUG
#ifdef SERVO_DEBUG
//调试输出动作组停止信息
Serial.print("StopServoActionGroup\n");
Serial.println("#SERVO: StopServoActionGroup");
#endif
}
@ -82,10 +82,10 @@ void Servo::SetActionGroupSpeed(uint8_t action_num, float speed)
SerialX->write(buf, 7); //发送数据帧
#ifdef DEBUG
#ifdef SERVO_DEBUG
//调试输出动作组速度设定信息
Serial.print("SetServoActionGroupSpeed: ");
Serial.println((int)action_num);
Serial.print("#SERVO: SetServoActionGroupSpeed: ");
Serial.print((int)action_num);
Serial.print(" Speed: ");
Serial.println(speed);
#endif

View File

@ -6,7 +6,7 @@
//注释以关闭调试功能
#define DEBUG
#define SERVO_DEBUG
#define SERVO_BAUD_RATE 9600