最终版本,完结撒花

This commit is contained in:
lxbpxylps@126.com 2021-06-05 21:29:07 +08:00
parent 987db4d8e9
commit 45c3b7159f
8 changed files with 111 additions and 32 deletions

View File

@ -23,7 +23,7 @@ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
#include <stdint.h> #include <stdint.h>
#include <NeoHWSerial.h> #include <NeoHWSerial.h>
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
/*! \mainpage /*! \mainpage

View File

@ -186,7 +186,7 @@ void HandleMessage(const char* message);
#include "MemoryUsage.h" #include "MemoryUsage.h"
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
#define DEBUG_BAUT_RATE 115200 #define DEBUG_BAUT_RATE 115200
int loop_time = 0; int loop_time = 0;
@ -237,7 +237,17 @@ void setup()
sensor.StartHMC5883(); sensor.StartHMC5883();
//在开始运行前依次检测各灰度传感器下方黑白是否正常 //在开始运行前依次检测各灰度传感器下方黑白是否正常
CheckGrayStatus(); //CheckGrayStatus();
while (1)
{
sensor.IsWhite(GRAY_1);
sensor.IsWhite(GRAY_2);
sensor.IsWhite(GRAY_3);
sensor.IsWhite(GRAY_4);
sensor.IsWhite(GRAY_5);
sensor.IsWhite(GRAY_6);
}
//前往 0, 0 //前往 0, 0
//沿线直行,到后端传感器接触下一条线离开函数 //沿线直行,到后端传感器接触下一条线离开函数
@ -812,7 +822,7 @@ void LineBackward(uint8_t end_position, uint8_t type, float speed_rate)
if (sensor.IsWhite(GRAY_1)) if (sensor.IsWhite(GRAY_1))
gray_match_a = true; gray_match_a = true;
if (sensor.IsWhite(GRAY_2)) if (sensor.IsWhite(GRAY_2))
gray_match_b = true; gray_match_b = true;
} }
else //后端接触线离开函数 else //后端接触线离开函数

View File

@ -8,7 +8,7 @@
#define RADIO_DEBUG #define RADIO_DEBUG
#ifdef RADIO_DEBUG #ifdef RADIO_DEBUG
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
#endif #endif
//默认与 HC-12 连接串口 //默认与 HC-12 连接串口

View File

@ -292,28 +292,97 @@ void Route::InitBaseRoute(void)
{ {
{0, 0, NORMAL_POINT}, {0, 0, NORMAL_POINT},
{0, 1, NORMAL_POINT}, {0, 1, NORMAL_POINT},
{0, 2, NORMAL_POINT}, {1, 1, CATCH_POINT},
{-1, 2, NORMAL_POINT}, {2, 1, NORMAL_POINT},
{2, 2, CARRY_POINT},
{2, 3, NORMAL_POINT},
{3, 3, GETOUT_POINT},
{2, 3, NORMAL_POINT},
{2, 4, NORMAL_POINT},
{3, 4, RELEASE_POINT},
{2, 4, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{1, 3, NORMAL_POINT},
{0, 3, NORMAL_POINT},
{-1, 3, NORMAL_POINT},
{-1, 4, GAIN_POINT},
{-1, 3, NORMAL_POINT},
{0, 3, NORMAL_POINT},
{1, 3, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{2, 4, NORMAL_POINT},
{3, 4, RELEASE_POINT},
{2, 4, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{1, 3, NORMAL_POINT},
{0, 3, NORMAL_POINT},
{0, 2, CATCH_POINT},
{1, 2, NORMAL_POINT},
{2, 2, NORMAL_POINT},
{3, 2, RELEASE_POINT},
{2, 2, NORMAL_POINT},
{1, 2, NORMAL_POINT},
{1, 1, NORMAL_POINT},
{0, 1, NORMAL_POINT},
{-1, 1, CATCH_POINT}, {-1, 1, CATCH_POINT},
{0, 1, NORMAL_POINT}, {-2, 1, NORMAL_POINT},
{0, 0, NORMAL_POINT}, {-2, 2, CARRY_POINT},
{-1, 0, RELEASE_POINT},
{0, 0, NORMAL_POINT},
{0, 1, NORMAL_POINT},
{0, 2, NORMAL_POINT},
{-1, 2, NORMAL_POINT}, {-1, 2, NORMAL_POINT},
{-1, 1, NORMAL_POINT},
{0, 1, NORMAL_POINT},
{0, 0, NORMAL_POINT},
{-1, 0, GAIN_POINT},
{0, 0, NORMAL_POINT},
{0, 1, NORMAL_POINT},
{0, 2, NORMAL_POINT}, {0, 2, NORMAL_POINT},
{0, 3, NORMAL_POINT},
{1, 3, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{3, 3, GETOUT_POINT},
{2, 3, NORMAL_POINT},
{2, 2, NORMAL_POINT},
{3, 2, RELEASE_POINT},
{-1, 1, CARRY_POINT},
{-2, 1, NORMAL_POINT},
{-2, 2, CARRY_POINT},
{-1, 2, NORMAL_POINT}, {-1, 2, NORMAL_POINT},
{-1, 1, NORMAL_POINT}, {0, 2, CATCH_POINT},
{0, 1, NORMAL_POINT}, {0, 3, NORMAL_POINT},
{0, 0, NORMAL_POINT}, {1, 3, NORMAL_POINT},
{-1, 0, RELEASE_POINT} {2, 3, NORMAL_POINT},
{3, 3, GETOUT_POINT},//
{2, 3, NORMAL_POINT},
{2, 4, NORMAL_POINT},
{3, 4, RELEASE_POINT},//
{2, 4, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{2, 2, CATCH_POINT},
{3, 2, RELEASE_POINT},//
{2, 2, NORMAL_POINT},
{2, 1, NORMAL_POINT},
{1, 1, CATCH_POINT},
{1, 2, NORMAL_POINT},
{1, 3, NORMAL_POINT},
{2, 3, NORMAL_POINT},
{2, 4, NORMAL_POINT},
{3, 4, RELEASE_POINT},//
{2, 4, NORMAL_POINT},
{2, 5, NORMAL_POINT},
{2, 6, CATCH_POINT},
{3, 6, RELEASE_POINT},//
{2, 6, NORMAL_POINT},
{2, 7, NORMAL_POINT},
{1, 7, CATCH_POINT},
{0, 7, NORMAL_POINT},
{0, 6, CARRY_POINT},
{0, 5, NORMAL_POINT},
{1, 5, NORMAL_POINT},
{2, 5, NORMAL_POINT},
{3, 5, GETOUT_POINT},//
{2, 5, NORMAL_POINT},
{2, 4, NORMAL_POINT},
{3, 4, RELEASE_POINT}//
}; };
//计算数组元素个数 //计算数组元素个数

View File

@ -8,7 +8,7 @@
#define ROUTE_DEBUG #define ROUTE_DEBUG
#ifdef ROUTE_DEBUG #ifdef ROUTE_DEBUG
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
#endif #endif
//坐标点操作定义 //坐标点操作定义

View File

@ -213,12 +213,12 @@ bool Sensor::IsPushed(uint8_t button_num)
NeoSerialDebug.print(F("#SENSOR: BUTTON_1: ")); NeoSerialDebug.print(F("#SENSOR: BUTTON_1: "));
else NeoSerialDebug.print(F("#SENSOR: BUTTON_2: ")); else NeoSerialDebug.print(F("#SENSOR: BUTTON_2: "));
if (button_val == LOW) if (button_val == HIGH)
NeoSerialDebug.println(F("pushed")); NeoSerialDebug.println(F("pushed"));
else NeoSerialDebug.println(F("released")); else NeoSerialDebug.println(F("released"));
#endif #endif
if (button_val == LOW) if (button_val == HIGH)
return true; return true;
else return false; else return false;
} }

View File

@ -6,7 +6,7 @@
#define SENSOR_DEBUG #define SENSOR_DEBUG
#ifdef SENSOR_DEBUG #ifdef SENSOR_DEBUG
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
#endif #endif
//灰度传感器 OUT 接口定义 //灰度传感器 OUT 接口定义
@ -48,15 +48,15 @@
#define GRAY_6 5 #define GRAY_6 5
#define GRAY_7 6 #define GRAY_7 6
//碰撞传感器 OUT 接口定义 //开关传感器 OUT 接口定义
#define BUTTON_1_OUT 2 #define BUTTON_1_OUT 2
#define BUTTON_2_OUT 3 #define BUTTON_2_OUT 3
//碰撞传感器 VCC 接口定义 //开关传感器 VCC 接口定义
#define BUTTON_1_VCC 45 #define BUTTON_1_VCC 45
#define BUTTON_2_VCC 46 #define BUTTON_2_VCC 46
//碰撞传感器标识定义 //开关传感器标识定义
#define BUTTON_1 0 #define BUTTON_1 0
#define BUTTON_2 1 #define BUTTON_2 1
@ -81,7 +81,7 @@ public:
//灰度传感器灰度值偏离比例,即 (gray_gate - gray_val) / gray_gate //灰度传感器灰度值偏离比例,即 (gray_gate - gray_val) / gray_gate
static float GrayDeviationRate(uint8_t gray_sensor_num); static float GrayDeviationRate(uint8_t gray_sensor_num);
//碰撞传感器(开关判断是否闭合 //开关判断是否闭合
static bool IsPushed(uint8_t button_num); static bool IsPushed(uint8_t button_num);
//开启 HMC5883 的 I2C 通讯 //开启 HMC5883 的 I2C 通讯

View File

@ -8,7 +8,7 @@
#define SERVO_DEBUG #define SERVO_DEBUG
#ifdef SERVO_DEBUG #ifdef SERVO_DEBUG
#define NeoSerialDebug NeoSerial3 #define NeoSerialDebug NeoSerial
#endif #endif
//与舵机控制板连接串口 //与舵机控制板连接串口