2021-03-21 23:32:51 +08:00
|
|
|
|
#include <Arduino.h>
|
|
|
|
|
|
#include <EEPROM.h>
|
|
|
|
|
|
#include <NeoHWSerial.h>
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
#include "moveTaiChi.h" //轮胎运动库
|
|
|
|
|
|
#include "sensorTaiChi.h" //传感器库
|
|
|
|
|
|
#include "servoTaiChi.h" //舵机库
|
2021-03-21 23:32:51 +08:00
|
|
|
|
#include "radioTaiChi.h" //通信库
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Move move; //轮胎运动实例
|
|
|
|
|
|
Sensor sensor; //传感器实例
|
|
|
|
|
|
Servo servo; //舵机实例
|
2021-03-21 23:32:51 +08:00
|
|
|
|
Radio radio; //通讯实例
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//****************************************运动路径****************************************
|
|
|
|
|
|
//坐标点操作定义
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#define NORMAL_POINT 0 //普通点
|
|
|
|
|
|
#define CATCH_POINT 1 //抓取点
|
|
|
|
|
|
#define RELEASE_POINT 2 //释放点(使用机械臂)
|
2021-02-21 19:28:17 +08:00
|
|
|
|
#define CARRY_POINT 3 //携带点(从底盘)
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#define GETOUT_POINT 4 //释放点(从底盘)
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define GAIN_POINT 5 //增益点
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
//坐标点数组定义
|
|
|
|
|
|
#define X 0
|
|
|
|
|
|
#define Y 1
|
|
|
|
|
|
#define TYPE 2
|
|
|
|
|
|
|
|
|
|
|
|
int8_t route[][3] =
|
|
|
|
|
|
{
|
2021-03-16 19:53:15 +08:00
|
|
|
|
{0, 0, NORMAL_POINT},
|
|
|
|
|
|
{0, 1, NORMAL_POINT},
|
|
|
|
|
|
{0, 2, NORMAL_POINT},
|
|
|
|
|
|
{-1, 2, NORMAL_POINT},
|
|
|
|
|
|
{-1, 1, CATCH_POINT},
|
|
|
|
|
|
{0, 1, NORMAL_POINT},
|
|
|
|
|
|
{0, 0, NORMAL_POINT},
|
|
|
|
|
|
{-1, 0, RELEASE_POINT},
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{0, 0, NORMAL_POINT},
|
|
|
|
|
|
{0, 1, NORMAL_POINT},
|
2021-03-10 23:41:12 +08:00
|
|
|
|
{0, 2, NORMAL_POINT},
|
|
|
|
|
|
{-1, 2, NORMAL_POINT},
|
2021-03-16 09:05:51 +08:00
|
|
|
|
{-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},
|
|
|
|
|
|
{-1, 2, NORMAL_POINT},
|
|
|
|
|
|
{-1, 1, NORMAL_POINT},
|
2021-03-10 23:41:12 +08:00
|
|
|
|
{0, 1, NORMAL_POINT},
|
|
|
|
|
|
{0, 0, NORMAL_POINT},
|
|
|
|
|
|
{-1, 0, RELEASE_POINT}
|
2021-02-14 12:50:42 +08:00
|
|
|
|
};
|
|
|
|
|
|
//***************************************************************************************
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//****************************************可调参数****************************************
|
2021-03-21 23:32:51 +08:00
|
|
|
|
//EEPROM 写入位置
|
|
|
|
|
|
#define EEPROM_ADDRESS 0x0
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//是否关闭爪子状态检测功能
|
|
|
|
|
|
#define DISABLE_CLAW_CHECK
|
|
|
|
|
|
|
2021-02-18 11:31:28 +08:00
|
|
|
|
//抓取点移动用时
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define CATCH_MOVE_DELAY_TIME 500
|
|
|
|
|
|
//释放点向前移动用时
|
|
|
|
|
|
#define RELEASE_MOVE_FORWARD_DELAY_TIME 1000
|
|
|
|
|
|
//释放点暂停用时
|
2021-03-16 09:05:51 +08:00
|
|
|
|
#define STOP_DELAY_TIME 500
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//释放点向后向前移动用时
|
|
|
|
|
|
#define RELEASE_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME 460
|
|
|
|
|
|
//增益点向后向前移动用时
|
2021-03-16 09:05:51 +08:00
|
|
|
|
#define GAIN_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME 750
|
|
|
|
|
|
//增益点稍稍向前移动推环用时
|
|
|
|
|
|
#define GAIN_MOVE_FORWARD_TO_PUSH_DELAY_TIME 200
|
|
|
|
|
|
//增益点稍稍向后移动抓取用时
|
|
|
|
|
|
#define GAIN_MOVE_BACKWARD_TO_CATCH_DELAY_TIME 100
|
|
|
|
|
|
//增益点稍稍向后移动拉环用时
|
|
|
|
|
|
#define GAIN_MOVE_BACKWARD_TO_UP_DELAY_TIME 65
|
2021-02-14 15:44:39 +08:00
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//重置留时
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define RESET_DELAY_TIME 1600
|
|
|
|
|
|
//放下爪子用时
|
|
|
|
|
|
#define DOWN_DELAY_TIME 1600
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//抓取留时
|
2021-03-16 19:53:15 +08:00
|
|
|
|
#define CATCH_DELAY_TIME 600
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//释放留时
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define RELEASE_DELAY_TIME 3100
|
|
|
|
|
|
//增益放下爪子用时
|
|
|
|
|
|
#define GAINDOWN_DELAY_TIME 1600
|
|
|
|
|
|
//增益抓取用时
|
2021-03-16 09:05:51 +08:00
|
|
|
|
#define GAINCATCH_DELAY_TIME 1600
|
|
|
|
|
|
//增益抬起爪子用时
|
2021-03-16 19:53:15 +08:00
|
|
|
|
#define GAINUP_DELAY_TIME 1600
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-18 13:19:34 +08:00
|
|
|
|
//最大抓取尝试次数
|
|
|
|
|
|
#define MAX_CATCH_TIMES 2
|
|
|
|
|
|
|
2021-03-05 22:32:46 +08:00
|
|
|
|
//(前进转)从触碰白线到开始转向延时
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define BEFORE_FORTURN_DELAY 670
|
2021-03-05 22:32:46 +08:00
|
|
|
|
//(后退转)从触碰白线到开始转向延时
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define BEFORE_BACKTURN_DELAY 500
|
2021-03-05 22:32:46 +08:00
|
|
|
|
|
|
|
|
|
|
//开始转到开始检测是否摆正的延时
|
|
|
|
|
|
#define BEFORE_CHECK_STRAIGHT_DELAY 700
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//***************************************************************************************
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//****************************************全局变量****************************************
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//GND Pins
|
2021-03-21 23:32:51 +08:00
|
|
|
|
uint8_t gnd_pins[8] = {14, 15, 32, 33, 34, 35, 36, 37};
|
|
|
|
|
|
|
|
|
|
|
|
//EEPROM 储存的调试数据
|
|
|
|
|
|
struct StroageInfo
|
|
|
|
|
|
{
|
|
|
|
|
|
float real_angle_val[8];
|
|
|
|
|
|
int gray_7_gate;
|
|
|
|
|
|
int delay_time_after_turn;
|
|
|
|
|
|
} stroage_info;
|
|
|
|
|
|
|
|
|
|
|
|
//下一点绝对朝向角
|
|
|
|
|
|
float north_left_angle;
|
|
|
|
|
|
float north_right_angle;
|
|
|
|
|
|
float west_left_angle;
|
|
|
|
|
|
float west_right_angle;
|
|
|
|
|
|
float south_left_angle;
|
|
|
|
|
|
float south_right_angle;
|
|
|
|
|
|
float east_left_angle;
|
|
|
|
|
|
float east_right_angle;
|
|
|
|
|
|
|
|
|
|
|
|
//7 号传感器灰度临界值
|
|
|
|
|
|
int gray_7_gate;
|
|
|
|
|
|
|
|
|
|
|
|
//转向开始到结束的时间
|
|
|
|
|
|
int delay_time_after_turn;
|
2021-03-05 22:32:46 +08:00
|
|
|
|
|
2021-02-14 23:38:28 +08:00
|
|
|
|
//数组位置标记
|
2021-02-14 12:50:42 +08:00
|
|
|
|
int passed_flag = 0;
|
2021-02-14 23:38:28 +08:00
|
|
|
|
int next_flag = 1;
|
|
|
|
|
|
int next_next_flag = 2;
|
|
|
|
|
|
|
|
|
|
|
|
//最大数组位置标记
|
|
|
|
|
|
int max_flag;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
#define FRONT_NEXT 0
|
|
|
|
|
|
#define BACK_NEXT 1
|
|
|
|
|
|
//下一点朝向
|
|
|
|
|
|
uint8_t next_position = FRONT_NEXT;
|
2021-02-18 13:19:34 +08:00
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
#define NORTH 0
|
|
|
|
|
|
#define WEST 1
|
|
|
|
|
|
#define SOUTH 2
|
|
|
|
|
|
#define EAST 3
|
|
|
|
|
|
//下一点绝对朝向
|
|
|
|
|
|
uint8_t current_real_direction = NORTH;
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//爪子是否抓有环
|
|
|
|
|
|
bool is_claw_catch = false;
|
|
|
|
|
|
|
2021-02-18 13:19:34 +08:00
|
|
|
|
//爪子是否正常
|
|
|
|
|
|
bool is_claw_ok = true;
|
2021-02-21 19:28:17 +08:00
|
|
|
|
|
|
|
|
|
|
//底盘是否携带环
|
|
|
|
|
|
bool is_carry = false;
|
2021-03-21 23:32:51 +08:00
|
|
|
|
|
|
|
|
|
|
#define TURN_BY_TIME 0 //基于时间
|
|
|
|
|
|
#define TURN_BY_GRAY 1 //基于灰度传感器
|
|
|
|
|
|
#define TURN_BY_EARTH 2 //基于地磁场
|
|
|
|
|
|
//转向方式
|
|
|
|
|
|
uint8_t turn_method = TURN_BY_TIME;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//***************************************************************************************
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//****************************************自定函数****************************************
|
2021-03-05 22:32:46 +08:00
|
|
|
|
//设置接口低电平作为额外地
|
|
|
|
|
|
void SetGNDPins(void);
|
|
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
//从 EEPROM 读取数据
|
|
|
|
|
|
void ReadFromEEPROM(void);
|
|
|
|
|
|
|
2021-02-24 18:23:52 +08:00
|
|
|
|
//在开始运行前依次检测各灰度传感器下方黑白是否正常,若不正常,异常传感器闪烁,程序不继续进行
|
|
|
|
|
|
void CheckGrayStatus(void);
|
2021-02-24 18:10:38 +08:00
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
#define NO_JUMP 0
|
|
|
|
|
|
#define JUMP_DEAD_ROAD 1
|
|
|
|
|
|
//更新标记
|
|
|
|
|
|
void UpdateFlag(uint8_t jump_choice = NO_JUMP);
|
|
|
|
|
|
|
2021-02-15 10:58:46 +08:00
|
|
|
|
//计算方向,同时更改完成转向后相对下一点的朝向
|
2021-02-14 12:50:42 +08:00
|
|
|
|
uint8_t CalcDirection(void);
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//由灰度比计算修正减速比
|
|
|
|
|
|
float CalcFixSpeedRate(float gray_deviation_rate);
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
#define FRONT_END 0
|
|
|
|
|
|
#define BACK_END 1
|
|
|
|
|
|
#define CATCH_END 2
|
|
|
|
|
|
#define RELEASE_END 3
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,在触发条件后离开函数但不停止
|
2021-02-15 11:01:17 +08:00
|
|
|
|
void LineForward(uint8_t end_position, float speed_rate = 1.0);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线后退,在触发条件后离开函数但不停止
|
2021-02-15 11:01:17 +08:00
|
|
|
|
void LineBackward(uint8_t end_position, float speed_rate = 1.0);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
//直行或后退或转向,完成后离开函数但不停止。会自动跳过无需前往的释放点
|
2021-02-15 19:17:59 +08:00
|
|
|
|
void TurnDirection(float speed_rate = 1.0);
|
2021-02-17 19:35:43 +08:00
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#define CATCH_TYPE_CATCH 0
|
|
|
|
|
|
#define CATCH_TYPE_GAIN 1
|
2021-02-17 19:35:43 +08:00
|
|
|
|
//抓取环,并判定是否抓取成功
|
2021-03-10 23:41:12 +08:00
|
|
|
|
bool CatchAndCheck(uint8_t type = CATCH_TYPE_CATCH, float speed = 1.0);
|
2021-02-18 13:33:55 +08:00
|
|
|
|
|
|
|
|
|
|
//打开爪子,并判断爪子是否能正常工作
|
|
|
|
|
|
bool OpenClawAndCheck(void);
|
2021-03-21 23:32:51 +08:00
|
|
|
|
|
|
|
|
|
|
//通讯消息处理函数
|
|
|
|
|
|
void HandleMessage(char * message);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//***************************************************************************************
|
2021-02-10 20:13:28 +08:00
|
|
|
|
|
|
|
|
|
|
|
2021-02-18 15:13:40 +08:00
|
|
|
|
//****************************************调试相关****************************************
|
|
|
|
|
|
//注释以关闭调试功能
|
|
|
|
|
|
#define TAICHI_DEBUG
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
|
|
|
|
|
|
#define DEBUG_BAUT_RATE 115200
|
|
|
|
|
|
|
|
|
|
|
|
int loop_time = 0;
|
|
|
|
|
|
|
|
|
|
|
|
//错误消息函数,用于在出现致命错误后结束程序
|
|
|
|
|
|
void DebugCanNotContinue(char* message)
|
|
|
|
|
|
{
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.print("#TAICHI: CAN NOT CONTINUE WHEN "); NeoSerial.println(message);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: loop_time: "); NeoSerial.println(loop_time);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: pass: ["); NeoSerial.print(route[passed_flag][X]); NeoSerial.print(", "); NeoSerial.print(route[passed_flag][Y]); NeoSerial.print("]");
|
|
|
|
|
|
NeoSerial.print(" flag: "); NeoSerial.print(passed_flag);
|
|
|
|
|
|
NeoSerial.print(" TYPE: "); NeoSerial.println((int)route[passed_flag][TYPE]);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: next: ["); NeoSerial.print(route[next_flag][X]); NeoSerial.print(", "); NeoSerial.print(route[next_flag][Y]); NeoSerial.print("]");
|
|
|
|
|
|
NeoSerial.print(" next_position: "); NeoSerial.print((int)next_position);
|
|
|
|
|
|
NeoSerial.print(" TYPE: "); NeoSerial.println((int)route[next_flag][TYPE]);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: is_claw_catch: "); NeoSerial.print((int)is_claw_catch); NeoSerial.print(" is_claw_ok: "); NeoSerial.println((int)is_claw_ok);
|
2021-02-18 15:13:40 +08:00
|
|
|
|
|
|
|
|
|
|
while (1) {}
|
|
|
|
|
|
}
|
|
|
|
|
|
#endif
|
|
|
|
|
|
//***************************************************************************************
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-17 12:42:28 +08:00
|
|
|
|
void setup()
|
2021-02-10 20:13:28 +08:00
|
|
|
|
{
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.begin(DEBUG_BAUT_RATE);
|
|
|
|
|
|
NeoSerial.println("#TAICHI: ======================setup()=====================");
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-03-05 22:32:46 +08:00
|
|
|
|
SetGNDPins();
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
move.Stop();
|
2021-03-21 23:32:51 +08:00
|
|
|
|
|
|
|
|
|
|
servo.BeginTransmit();
|
2021-02-14 12:50:42 +08:00
|
|
|
|
servo.StopAndReset();
|
|
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
radio.SetHandleMessageFunction(HandleMessage);
|
|
|
|
|
|
radio.BeginTransmit();
|
|
|
|
|
|
|
|
|
|
|
|
//从 EEPROM 读取数据
|
|
|
|
|
|
ReadFromEEPROM();
|
|
|
|
|
|
|
|
|
|
|
|
//开启 HMC5883 的 I2C 通讯
|
|
|
|
|
|
sensor.StartHMC5883();
|
|
|
|
|
|
|
2021-02-24 18:23:52 +08:00
|
|
|
|
//在开始运行前依次检测各灰度传感器下方黑白是否正常
|
|
|
|
|
|
CheckGrayStatus();
|
2021-02-24 18:10:38 +08:00
|
|
|
|
|
2021-02-14 23:38:28 +08:00
|
|
|
|
//计算最大数组下标
|
|
|
|
|
|
max_flag = sizeof(route) / sizeof(route[0]) - 1;
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//前往 0, 0
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,到后端传感器接触下一条线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineForward(BACK_END);
|
2021-02-10 20:13:28 +08:00
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//已越过 0, 0 正式进入循环
|
2021-02-10 20:13:28 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
void loop()
|
2021-02-10 20:13:28 +08:00
|
|
|
|
{
|
2021-02-15 13:14:46 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-02-17 12:42:28 +08:00
|
|
|
|
loop_time++;
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: ====================New loop()====================");
|
|
|
|
|
|
NeoSerial.print("#TAICHI: loop_time: "); NeoSerial.println(loop_time);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: pass: ["); NeoSerial.print(route[passed_flag][X]); NeoSerial.print(", "); NeoSerial.print(route[passed_flag][Y]); NeoSerial.print("]");
|
|
|
|
|
|
NeoSerial.print(" flag: "); NeoSerial.print(passed_flag);
|
|
|
|
|
|
NeoSerial.print(" TYPE: "); NeoSerial.println((int)route[passed_flag][TYPE]);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: next: ["); NeoSerial.print(route[next_flag][X]); NeoSerial.print(", "); NeoSerial.print(route[next_flag][Y]); NeoSerial.print("]");
|
|
|
|
|
|
NeoSerial.print(" next_position: "); NeoSerial.print((int)next_position);
|
|
|
|
|
|
NeoSerial.print(" TYPE: "); NeoSerial.println((int)route[next_flag][TYPE]);
|
|
|
|
|
|
NeoSerial.print("#TAICHI: is_claw_catch: "); NeoSerial.print((int)is_claw_catch); NeoSerial.print(" is_claw_ok: "); NeoSerial.println((int)is_claw_ok);
|
2021-02-15 13:14:46 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
int8_t& passed_flag_type = route[passed_flag][TYPE];
|
|
|
|
|
|
int8_t& next_flag_type = route[next_flag][TYPE];
|
|
|
|
|
|
int8_t& next_next_flag_type = route[next_next_flag][TYPE];
|
|
|
|
|
|
|
|
|
|
|
|
//情况一:刚完整经过普通点,下一个点为普通点或携带点
|
|
|
|
|
|
if (passed_flag_type == NORMAL_POINT && (next_flag_type == NORMAL_POINT || next_flag_type == CARRY_POINT))
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-15 10:58:46 +08:00
|
|
|
|
if (next_position == FRONT_NEXT)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,到前端传感器接触下一条线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineForward(FRONT_END);
|
2021-02-21 19:28:17 +08:00
|
|
|
|
|
|
|
|
|
|
//若下一点为携带点
|
|
|
|
|
|
if (next_flag_type == CARRY_POINT)
|
|
|
|
|
|
{
|
|
|
|
|
|
//底盘携带
|
|
|
|
|
|
is_carry = true;
|
|
|
|
|
|
|
|
|
|
|
|
//越过点成为普通点
|
|
|
|
|
|
next_flag_type = NORMAL_POINT;
|
|
|
|
|
|
}
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线后退,到后端传感器接触下一条线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineBackward(BACK_END);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//继续直行或后退或转向
|
2021-02-15 19:17:59 +08:00
|
|
|
|
TurnDirection();
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
//情况二:刚完整经过普通点,下一个点为抓取点
|
2021-02-21 19:28:17 +08:00
|
|
|
|
else if (passed_flag_type == NORMAL_POINT && next_flag_type == CATCH_POINT)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-18 14:31:51 +08:00
|
|
|
|
if (!is_claw_catch && !is_claw_ok) //爪子上无环且状态不正常
|
|
|
|
|
|
{
|
|
|
|
|
|
move.Stop(); //停止前进
|
|
|
|
|
|
OpenClawAndCheck(); //再次检测爪子是否正常
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
if (!is_claw_catch && is_claw_ok) //爪子上无环且状态正常
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
move.Stop(); //停止前进
|
|
|
|
|
|
|
|
|
|
|
|
servo.Down(); //放下爪子
|
|
|
|
|
|
delay(DOWN_DELAY_TIME);
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,在抓取位置离开函数
|
|
|
|
|
|
LineForward(CATCH_END);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//抓取
|
2021-02-21 19:28:17 +08:00
|
|
|
|
if (!CatchAndCheck())
|
2021-03-10 23:41:12 +08:00
|
|
|
|
is_carry = true; //抓取失败,视为底盘携带
|
2021-02-21 19:28:17 +08:00
|
|
|
|
}
|
|
|
|
|
|
else //未进行抓取
|
|
|
|
|
|
{
|
|
|
|
|
|
is_carry = true;
|
2021-02-18 14:31:51 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//继续沿线直行,到前端传感器接触下一条线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineForward(FRONT_END);
|
|
|
|
|
|
|
2021-02-14 13:44:18 +08:00
|
|
|
|
//继续直行或后退或转向
|
2021-02-15 19:17:59 +08:00
|
|
|
|
TurnDirection();
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//将越过的点视为普通点。因为即使抓取失败,环也会被携带在底盘内
|
2021-02-21 19:28:17 +08:00
|
|
|
|
next_flag_type = NORMAL_POINT;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-17 19:52:59 +08:00
|
|
|
|
//情况三:刚完整经过普通点,下一个点为释放点(使用机械臂)
|
2021-02-21 19:28:17 +08:00
|
|
|
|
else if (passed_flag_type == NORMAL_POINT && next_flag_type == RELEASE_POINT)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//沿线直行,在释放柱离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineForward(RELEASE_END);
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
2021-03-16 09:05:51 +08:00
|
|
|
|
delay(STOP_DELAY_TIME);
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//无循迹后退到真实释放位置
|
|
|
|
|
|
move.Backward();
|
|
|
|
|
|
delay(RELEASE_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME);
|
|
|
|
|
|
|
|
|
|
|
|
//停止后退
|
|
|
|
|
|
move.Stop();
|
2021-02-18 14:31:51 +08:00
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
//释放
|
|
|
|
|
|
servo.Release();
|
|
|
|
|
|
delay(RELEASE_DELAY_TIME); //释放留时
|
|
|
|
|
|
is_claw_catch = false;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//机械臂复原
|
|
|
|
|
|
servo.Reset();
|
|
|
|
|
|
|
|
|
|
|
|
//无循迹前进到释放柱
|
|
|
|
|
|
move.Forward();
|
|
|
|
|
|
delay(RELEASE_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME);
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//下一点朝向为后
|
2021-02-14 12:50:42 +08:00
|
|
|
|
next_position = BACK_NEXT;
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
2021-03-16 09:05:51 +08:00
|
|
|
|
delay(STOP_DELAY_TIME);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//情况四:刚完整经过释放点(使用机械臂)或增益抓取点,下一个点为普通点
|
|
|
|
|
|
else if ((passed_flag_type == RELEASE_POINT || passed_flag_type == GAIN_POINT) && next_flag_type == NORMAL_POINT)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//底盘携带清空
|
|
|
|
|
|
is_carry = false;
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线后退,到后端传感器接触下一条线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineBackward(BACK_END);
|
|
|
|
|
|
|
|
|
|
|
|
//继续后退或转向
|
2021-02-15 19:17:59 +08:00
|
|
|
|
TurnDirection();
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-17 19:52:59 +08:00
|
|
|
|
//情况五:刚完整经过普通点,下一个点为释放点(从底盘)
|
2021-02-21 19:28:17 +08:00
|
|
|
|
else if (passed_flag_type == NORMAL_POINT && next_flag_type == GETOUT_POINT)
|
2021-02-17 19:52:59 +08:00
|
|
|
|
{
|
2021-03-16 09:05:51 +08:00
|
|
|
|
//沿线直行,到前端传感器接触下一条线离开函数
|
|
|
|
|
|
LineForward(FRONT_END);
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,到后端传感器接触下一条线离开函数
|
2021-02-17 19:52:59 +08:00
|
|
|
|
LineForward(BACK_END);
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
|
2021-02-17 19:52:59 +08:00
|
|
|
|
//下一点朝向为后
|
|
|
|
|
|
next_position = BACK_NEXT;
|
|
|
|
|
|
}
|
|
|
|
|
|
//情况六:刚完整经过释放点(从底盘),下一个点为普通点
|
2021-02-21 19:28:17 +08:00
|
|
|
|
else if (passed_flag_type == GETOUT_POINT && next_flag_type == NORMAL_POINT)
|
2021-02-17 19:52:59 +08:00
|
|
|
|
{
|
2021-02-18 15:13:40 +08:00
|
|
|
|
//沿线后退,到前端传感器接触线离开函数
|
|
|
|
|
|
LineBackward(FRONT_END);
|
2021-02-21 19:28:17 +08:00
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//底盘携带清空
|
2021-02-21 19:28:17 +08:00
|
|
|
|
is_carry = false;
|
2021-02-18 15:13:40 +08:00
|
|
|
|
|
|
|
|
|
|
//沿线后退,到后端传感器接触线离开函数
|
2021-02-17 19:52:59 +08:00
|
|
|
|
LineBackward(BACK_END);
|
|
|
|
|
|
|
|
|
|
|
|
//继续后退或转向
|
|
|
|
|
|
TurnDirection();
|
|
|
|
|
|
}
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//情况七:刚完整经过普通点,下一个点为增益抓取点
|
|
|
|
|
|
else if (passed_flag_type == NORMAL_POINT && next_flag_type == GAIN_POINT)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (!is_claw_ok) //爪子状态不正常
|
|
|
|
|
|
{
|
|
|
|
|
|
move.Stop(); //停止前进
|
|
|
|
|
|
OpenClawAndCheck(); //再次检测爪子是否正常
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
if (is_claw_ok) //爪子状态正常
|
|
|
|
|
|
{
|
|
|
|
|
|
//沿线直行,在释放柱(增益柱)离开函数
|
|
|
|
|
|
LineForward(RELEASE_END);
|
|
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
2021-03-16 09:05:51 +08:00
|
|
|
|
delay(STOP_DELAY_TIME);
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//无循迹后退到真实抓取位置
|
|
|
|
|
|
move.Backward();
|
|
|
|
|
|
delay(GAIN_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME);
|
|
|
|
|
|
|
|
|
|
|
|
//停止后退
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
|
|
|
|
|
|
//放下爪子
|
|
|
|
|
|
servo.GainDown();
|
|
|
|
|
|
delay(GAINDOWN_DELAY_TIME);
|
|
|
|
|
|
|
2021-03-16 09:05:51 +08:00
|
|
|
|
//稍稍无循迹前进,向前推环,以约束环的位置
|
|
|
|
|
|
move.Forward(0.5);
|
|
|
|
|
|
delay(GAIN_MOVE_FORWARD_TO_PUSH_DELAY_TIME);
|
|
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
delay(STOP_DELAY_TIME);
|
|
|
|
|
|
|
|
|
|
|
|
//稍稍无循迹后退,便于爪子抓取
|
|
|
|
|
|
move.Backward(0.5);
|
|
|
|
|
|
delay(GAIN_MOVE_BACKWARD_TO_CATCH_DELAY_TIME);
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
|
|
|
|
|
|
//抓取
|
|
|
|
|
|
CatchAndCheck(CATCH_TYPE_GAIN);
|
|
|
|
|
|
|
2021-03-16 09:05:51 +08:00
|
|
|
|
//稍稍无循迹后退,便于爪子抬起
|
|
|
|
|
|
move.Backward(0.5);
|
|
|
|
|
|
delay(GAIN_MOVE_BACKWARD_TO_UP_DELAY_TIME);
|
|
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
|
|
|
|
|
|
//抬起爪子
|
|
|
|
|
|
servo.GainUp();
|
|
|
|
|
|
delay(GAINUP_DELAY_TIME);
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//无循迹前进到释放柱(增益柱)
|
|
|
|
|
|
move.Forward();
|
|
|
|
|
|
delay(GAIN_MOVE_BACKWARD_AND_FORWARD_DELAY_TIME);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//下一点朝向为后
|
|
|
|
|
|
next_position = BACK_NEXT;
|
|
|
|
|
|
|
|
|
|
|
|
//停止前进
|
|
|
|
|
|
move.Stop();
|
2021-03-16 09:05:51 +08:00
|
|
|
|
delay(STOP_DELAY_TIME);
|
2021-03-10 23:41:12 +08:00
|
|
|
|
}
|
2021-02-15 18:28:33 +08:00
|
|
|
|
//出现错误
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
|
|
|
|
|
move.Stop();
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-02-18 15:13:40 +08:00
|
|
|
|
DebugCanNotContinue("CHOOSE LOOP");
|
2021-02-15 18:28:33 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
}
|
2021-02-14 23:38:28 +08:00
|
|
|
|
|
|
|
|
|
|
//更新标记,继续循环
|
2021-02-21 19:28:17 +08:00
|
|
|
|
UpdateFlag();
|
2021-02-15 13:14:46 +08:00
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: ====================End loop()====================");
|
2021-02-15 13:14:46 +08:00
|
|
|
|
#endif
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-03-05 22:32:46 +08:00
|
|
|
|
//设置接口低电平作为额外地
|
|
|
|
|
|
void SetGNDPins(void)
|
|
|
|
|
|
{
|
2021-03-21 23:32:51 +08:00
|
|
|
|
uint8_t pin_num = sizeof(gnd_pins) / sizeof(uint8_t);
|
2021-03-05 22:32:46 +08:00
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
for (uint8_t i = 0; i < pin_num; i++)
|
2021-03-05 22:32:46 +08:00
|
|
|
|
{
|
|
|
|
|
|
pinMode(gnd_pins[i], OUTPUT);
|
|
|
|
|
|
digitalWrite(gnd_pins[i], LOW);
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
//从 EEPROM 读取数据
|
|
|
|
|
|
void ReadFromEEPROM(void)
|
|
|
|
|
|
{
|
|
|
|
|
|
//从 EEPROM 读取调试数据
|
|
|
|
|
|
EEPROM.get(EEPROM_ADDRESS, stroage_info);
|
|
|
|
|
|
|
|
|
|
|
|
//转向角度
|
|
|
|
|
|
north_left_angle = stroage_info.real_angle_val[0];
|
|
|
|
|
|
north_right_angle = stroage_info.real_angle_val[1];
|
|
|
|
|
|
west_left_angle = stroage_info.real_angle_val[2];
|
|
|
|
|
|
west_right_angle = stroage_info.real_angle_val[3];
|
|
|
|
|
|
south_left_angle = stroage_info.real_angle_val[4];
|
|
|
|
|
|
south_right_angle = stroage_info.real_angle_val[5];
|
|
|
|
|
|
east_left_angle = stroage_info.real_angle_val[6];
|
|
|
|
|
|
east_right_angle = stroage_info.real_angle_val[7];
|
|
|
|
|
|
|
|
|
|
|
|
//转向灰度值
|
|
|
|
|
|
sensor.SetGrayGate(GRAY_7, stroage_info.gray_7_gate);
|
|
|
|
|
|
|
|
|
|
|
|
//转向时间
|
|
|
|
|
|
delay_time_after_turn = stroage_info.delay_time_after_turn;
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
NeoSerial.println("#TAICHI: Data based on EEPROM : ");
|
|
|
|
|
|
NeoSerial.print("north_left_angle: "); NeoSerial.println(north_left_angle);
|
|
|
|
|
|
NeoSerial.print("north_right_angle: "); NeoSerial.println(north_right_angle);
|
|
|
|
|
|
NeoSerial.print("west_left_angle: "); NeoSerial.println(west_left_angle);
|
|
|
|
|
|
NeoSerial.print("west_right_angle: "); NeoSerial.println(west_right_angle);
|
|
|
|
|
|
NeoSerial.print("south_left_angle: "); NeoSerial.println(south_left_angle);
|
|
|
|
|
|
NeoSerial.print("south_right_angle: "); NeoSerial.println(south_right_angle);
|
|
|
|
|
|
NeoSerial.print("east_left_angle: "); NeoSerial.println(east_left_angle);
|
|
|
|
|
|
NeoSerial.print("east_right_angle: "); NeoSerial.println(east_right_angle);
|
|
|
|
|
|
NeoSerial.print("gray_7_gate: "); NeoSerial.println(stroage_info.gray_7_gate);
|
|
|
|
|
|
NeoSerial.print("delay_time_after_turn: "); NeoSerial.println(delay_time_after_turn);
|
|
|
|
|
|
#endif
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-24 18:23:52 +08:00
|
|
|
|
//在开始运行前依次检测各灰度传感器下方黑白是否正常,若不正常,异常传感器闪烁,程序不继续进行
|
|
|
|
|
|
void CheckGrayStatus(void)
|
2021-02-24 18:10:38 +08:00
|
|
|
|
{
|
2021-03-21 23:32:51 +08:00
|
|
|
|
//若正常,1 2 5 6 号传感器检测到黑色,3 4 号传感器检测到白色
|
|
|
|
|
|
//若一开始就采用灰度转弯,7 号也应检测到白色
|
2021-02-24 18:23:52 +08:00
|
|
|
|
bool is_status_right = false;
|
2021-02-24 18:10:38 +08:00
|
|
|
|
|
2021-02-24 18:23:52 +08:00
|
|
|
|
while (!is_status_right)
|
2021-02-24 18:10:38 +08:00
|
|
|
|
{
|
|
|
|
|
|
if (sensor.IsWhite(GRAY_1))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_1);
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_2))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_2);
|
|
|
|
|
|
else if (!sensor.IsWhite(GRAY_3))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_3);
|
|
|
|
|
|
else if (!sensor.IsWhite(GRAY_4))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_4);
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_5))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_5);
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_6))
|
|
|
|
|
|
sensor.FlashGraySensor(GRAY_6);
|
2021-03-21 23:32:51 +08:00
|
|
|
|
else if (turn_method == TURN_BY_GRAY && !sensor.IsWhite(GRAY_7))
|
2021-03-05 22:32:46 +08:00
|
|
|
|
sensor.FlashGraySensor(GRAY_7);
|
2021-02-24 18:23:52 +08:00
|
|
|
|
else is_status_right = true;
|
2021-02-24 18:10:38 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: Gray Sensor Status OK!");
|
2021-02-24 18:10:38 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
//更新标记
|
|
|
|
|
|
void UpdateFlag(uint8_t jump_choice)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (jump_choice == NO_JUMP)
|
|
|
|
|
|
{
|
|
|
|
|
|
passed_flag = next_flag;
|
|
|
|
|
|
|
|
|
|
|
|
next_flag = next_next_flag;
|
|
|
|
|
|
|
|
|
|
|
|
if (++next_next_flag > max_flag)
|
|
|
|
|
|
next_next_flag = 0;
|
|
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
|
|
|
|
|
int current_passed_flag = passed_flag;
|
|
|
|
|
|
|
|
|
|
|
|
UpdateFlag(NO_JUMP);
|
|
|
|
|
|
UpdateFlag(NO_JUMP);
|
|
|
|
|
|
|
|
|
|
|
|
passed_flag = current_passed_flag;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-15 10:58:46 +08:00
|
|
|
|
//计算方向,同时更改完成转向后相对下一点的朝向
|
2021-02-14 12:50:42 +08:00
|
|
|
|
uint8_t CalcDirection(void)
|
|
|
|
|
|
{
|
|
|
|
|
|
//计算第三点与第一点的相对坐标 rx0, ry0
|
2021-02-14 23:38:28 +08:00
|
|
|
|
int8_t rx0 = route[next_next_flag][X] - route[passed_flag][X];
|
|
|
|
|
|
int8_t ry0 = route[next_next_flag][Y] - route[passed_flag][Y];
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
//计算当前小车朝向的方向向量 vx, vy
|
2021-02-14 23:38:28 +08:00
|
|
|
|
int8_t vx = route[next_flag][X] - route[passed_flag][X];
|
|
|
|
|
|
int8_t vy = route[next_flag][Y] - route[passed_flag][Y];
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
//坐标旋转变换
|
|
|
|
|
|
int8_t rx, ry;
|
|
|
|
|
|
if (vx == 0 && vy == 1)
|
|
|
|
|
|
{
|
|
|
|
|
|
rx = rx0;
|
|
|
|
|
|
ry = ry0;
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (vx == -1 && vy == 0)
|
|
|
|
|
|
{
|
|
|
|
|
|
rx = ry0;
|
|
|
|
|
|
ry = -rx0;
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (vx == 0 && vy == -1)
|
|
|
|
|
|
{
|
|
|
|
|
|
rx = -rx0;
|
|
|
|
|
|
ry = -ry0;
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (vx == 1 && vy == 0)
|
|
|
|
|
|
{
|
|
|
|
|
|
rx = -ry0;
|
|
|
|
|
|
ry = rx0;
|
|
|
|
|
|
}
|
2021-02-24 21:38:42 +08:00
|
|
|
|
else DebugCanNotContinue("CALC DIRECTION <1>"); //调试用
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
//判断行进方向
|
|
|
|
|
|
if (rx == 0 && ry == 2)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (next_position == FRONT_NEXT)
|
|
|
|
|
|
{
|
2021-02-14 13:36:38 +08:00
|
|
|
|
return FORWARD;
|
|
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
|
|
|
|
|
return BACKWARD;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (rx == 0 && ry == 0)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (next_position == FRONT_NEXT)
|
|
|
|
|
|
{
|
|
|
|
|
|
next_position = BACK_NEXT;
|
|
|
|
|
|
return BACKWARD;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else
|
2021-02-14 13:36:38 +08:00
|
|
|
|
{
|
|
|
|
|
|
next_position = FRONT_NEXT;
|
|
|
|
|
|
return FORWARD;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (rx == -1 && ry == 1)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (next_position == FRONT_NEXT)
|
|
|
|
|
|
{
|
2021-02-14 13:36:38 +08:00
|
|
|
|
return FORLEFTWARD;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
2021-02-14 13:36:38 +08:00
|
|
|
|
next_position = FRONT_NEXT;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
return BACKLEFTWARD;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (rx == 1 && ry == 1)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (next_position == FRONT_NEXT)
|
|
|
|
|
|
{
|
2021-02-14 13:36:38 +08:00
|
|
|
|
return FORRIGHTWARD;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
2021-02-14 13:36:38 +08:00
|
|
|
|
next_position = FRONT_NEXT;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
return BACKRIGHTWARD;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
2021-02-24 21:38:42 +08:00
|
|
|
|
else DebugCanNotContinue("CALC DIRECTION <2>"); //调试用
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//由灰度比计算修正减速比
|
|
|
|
|
|
float CalcFixSpeedRate(float gray_deviation_rate)
|
|
|
|
|
|
{
|
|
|
|
|
|
return -50.0 * pow((gray_deviation_rate - 1.0), 2.0) + 1.0;
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,在触发条件后离开函数但不停止
|
2021-02-15 11:01:17 +08:00
|
|
|
|
void LineForward(uint8_t end_position, float speed_rate)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出沿线直行状态
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.print("#TAICHI: Line Forward");
|
|
|
|
|
|
NeoSerial.print(" end_position: ");
|
|
|
|
|
|
NeoSerial.println((int)end_position);
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
//记录开始时间
|
2021-02-18 11:31:28 +08:00
|
|
|
|
unsigned long begin_time = millis();
|
2021-03-16 19:53:15 +08:00
|
|
|
|
//记录灰度传感器匹配情况
|
|
|
|
|
|
bool gray_match_a = false;
|
|
|
|
|
|
bool gray_match_b = false;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
|
|
|
|
|
|
while(1)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (!sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4)) //左侧越线
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
move.ForRightward(speed_rate, CalcFixSpeedRate(sensor.GrayDeviationRate(GRAY_3)));
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_3) && !sensor.IsWhite(GRAY_4)) //右侧越线
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
move.ForLeftward(speed_rate, CalcFixSpeedRate(sensor.GrayDeviationRate(GRAY_4)));
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4)) //在白线上
|
|
|
|
|
|
{
|
|
|
|
|
|
move.Forward(speed_rate);
|
|
|
|
|
|
}
|
|
|
|
|
|
else //均不符合,则低速后退,尝试回到白线上
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//move.Backward(LINE_FIND_SPEED_RATE);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
if (end_position == FRONT_END) //前端接触线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (sensor.IsWhite(GRAY_1))
|
|
|
|
|
|
gray_match_a = true;
|
|
|
|
|
|
|
|
|
|
|
|
if (sensor.IsWhite(GRAY_2))
|
|
|
|
|
|
gray_match_b = true;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-18 14:31:51 +08:00
|
|
|
|
else if (end_position == BACK_END) //后端接触线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (sensor.IsWhite(GRAY_5))
|
|
|
|
|
|
gray_match_a = true;
|
|
|
|
|
|
|
|
|
|
|
|
if (sensor.IsWhite(GRAY_6))
|
|
|
|
|
|
gray_match_b = true;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-18 14:31:51 +08:00
|
|
|
|
else if (end_position == CATCH_END) //到达抓取位置离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-18 11:31:28 +08:00
|
|
|
|
if (millis() - begin_time > CATCH_MOVE_DELAY_TIME)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
break;
|
|
|
|
|
|
}
|
2021-02-18 14:31:51 +08:00
|
|
|
|
else //到达释放位置离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
if (millis() - begin_time > RELEASE_MOVE_FORWARD_DELAY_TIME)
|
2021-02-14 15:44:39 +08:00
|
|
|
|
break;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//对应前端接触线离开函数和后端接触线离开函数的情况
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (gray_match_a && gray_match_b)
|
2021-03-10 23:41:12 +08:00
|
|
|
|
break;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-15 12:28:14 +08:00
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出沿线直行结束
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: End Line Forward");
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线后退,在触发条件后离开函数但不停止
|
2021-02-15 11:01:17 +08:00
|
|
|
|
void LineBackward(uint8_t end_position, float speed_rate)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出沿线后退状态
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.print("#TAICHI: Line Backward");
|
|
|
|
|
|
NeoSerial.print(" end_position: ");
|
|
|
|
|
|
NeoSerial.println((int)end_position);
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-03-16 19:53:15 +08:00
|
|
|
|
//记录灰度传感器匹配情况
|
|
|
|
|
|
bool gray_match_a = false;
|
|
|
|
|
|
bool gray_match_b = false;
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
while(1)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (!sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4)) //左侧越线
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
move.BackRightward(speed_rate, CalcFixSpeedRate(sensor.GrayDeviationRate(GRAY_3)));
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_3) && !sensor.IsWhite(GRAY_4)) //右侧越线
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
move.BackLeftward(speed_rate, CalcFixSpeedRate(sensor.GrayDeviationRate(GRAY_4)));
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else if (sensor.IsWhite(GRAY_3) && sensor.IsWhite(GRAY_4)) //在白线上
|
|
|
|
|
|
{
|
|
|
|
|
|
move.Backward(speed_rate);
|
|
|
|
|
|
}
|
|
|
|
|
|
else //均不符合,则低速前进,尝试回到白线上
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//move.Forward(LINE_FIND_SPEED_RATE);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
if (end_position == FRONT_END) //前端接触线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (sensor.IsWhite(GRAY_1))
|
|
|
|
|
|
gray_match_a = true;
|
|
|
|
|
|
|
|
|
|
|
|
if (sensor.IsWhite(GRAY_2))
|
|
|
|
|
|
gray_match_b = true;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-18 14:31:51 +08:00
|
|
|
|
else //后端接触线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (sensor.IsWhite(GRAY_5))
|
|
|
|
|
|
gray_match_a = true;
|
|
|
|
|
|
|
|
|
|
|
|
if (sensor.IsWhite(GRAY_6))
|
|
|
|
|
|
gray_match_b = true;
|
2021-02-18 14:31:51 +08:00
|
|
|
|
}
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
//对应前端接触线离开函数和后端接触线离开函数的情况
|
2021-03-16 19:53:15 +08:00
|
|
|
|
if (gray_match_a && gray_match_b)
|
2021-03-10 23:41:12 +08:00
|
|
|
|
break;
|
2021-02-15 12:28:14 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出沿线后退结束
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: End Line Backward");
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2021-02-21 19:28:17 +08:00
|
|
|
|
//直行或后退或转向,完成后离开函数但不停止。会自动跳过无需前往的释放点
|
2021-02-15 19:17:59 +08:00
|
|
|
|
void TurnDirection(float speed_rate)
|
2021-02-14 12:50:42 +08:00
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//若下下点为释放点或增益抓取点,判断是否需要跳过
|
|
|
|
|
|
if ((route[next_next_flag][TYPE] == RELEASE_POINT && (!is_claw_catch || is_carry))
|
|
|
|
|
|
|| (route[next_next_flag][TYPE] == GETOUT_POINT && !is_carry)
|
|
|
|
|
|
|| (route[next_next_flag][TYPE] == GAIN_POINT && is_claw_catch)
|
|
|
|
|
|
)
|
2021-02-21 19:28:17 +08:00
|
|
|
|
{
|
|
|
|
|
|
UpdateFlag(JUMP_DEAD_ROAD);
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出直行或后退或转向状态
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: JUMP THE RELEASE/GETOUT/GAIN POINT FOR STATUS REASON");
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#endif
|
2021-02-21 19:28:17 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
2021-02-15 19:17:59 +08:00
|
|
|
|
uint8_t direction = CalcDirection();
|
|
|
|
|
|
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出直行或后退或转向状态
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.print("#TAICHI: Turn Direction");
|
|
|
|
|
|
NeoSerial.print(" direction: ");
|
|
|
|
|
|
NeoSerial.println((int)direction);
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-02-14 12:50:42 +08:00
|
|
|
|
if (direction == FORWARD) //继续直行
|
|
|
|
|
|
{
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线直行,到后端传感器接触线离开函数
|
2021-02-14 12:50:42 +08:00
|
|
|
|
LineForward(BACK_END, speed_rate);
|
|
|
|
|
|
}
|
|
|
|
|
|
else if (direction == BACKWARD) //继续后退
|
|
|
|
|
|
{
|
2021-02-18 14:31:51 +08:00
|
|
|
|
//沿线后退,到前端传感器接触线离开函数
|
2021-02-14 23:38:28 +08:00
|
|
|
|
LineBackward(FRONT_END, speed_rate);
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
|
|
|
|
|
else //继续转向
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//等待小车旋转中心与十字中心重合
|
2021-03-05 22:32:46 +08:00
|
|
|
|
if (direction == FORLEFTWARD || direction == FORRIGHTWARD)
|
|
|
|
|
|
delay(BEFORE_FORTURN_DELAY);
|
|
|
|
|
|
else delay(BEFORE_BACKTURN_DELAY);
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//旋转
|
2021-02-14 12:50:42 +08:00
|
|
|
|
move.MoveDirection(direction, speed_rate);
|
2021-03-05 22:32:46 +08:00
|
|
|
|
|
2021-03-21 23:32:51 +08:00
|
|
|
|
//角度相关计算
|
|
|
|
|
|
float next_real_angle;
|
|
|
|
|
|
uint8_t next_real_direction;
|
|
|
|
|
|
if (direction == FORLEFTWARD || direction == BACKRIGHTWARD)
|
|
|
|
|
|
{
|
|
|
|
|
|
switch (current_real_direction)
|
|
|
|
|
|
{
|
|
|
|
|
|
case NORTH: next_real_direction = WEST; next_real_angle = west_left_angle; break;
|
|
|
|
|
|
case WEST: next_real_direction = SOUTH; next_real_angle = south_left_angle; break;
|
|
|
|
|
|
case SOUTH: next_real_direction = EAST; next_real_angle = east_left_angle; break;
|
|
|
|
|
|
case EAST: next_real_direction = NORTH; next_real_angle = north_left_angle;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
else
|
|
|
|
|
|
{
|
|
|
|
|
|
switch (current_real_direction)
|
|
|
|
|
|
{
|
|
|
|
|
|
case NORTH: next_real_direction = EAST; next_real_angle = east_right_angle; break;
|
|
|
|
|
|
case WEST: next_real_direction = NORTH; next_real_angle = north_right_angle; break;
|
|
|
|
|
|
case SOUTH: next_real_direction = WEST; next_real_angle = west_right_angle; break;
|
|
|
|
|
|
case EAST: next_real_direction = SOUTH; next_real_angle = south_right_angle;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//以不同方式判定结束
|
|
|
|
|
|
switch (turn_method)
|
|
|
|
|
|
{
|
|
|
|
|
|
case TURN_BY_TIME: //基于时间
|
|
|
|
|
|
{
|
|
|
|
|
|
delay(delay_time_after_turn);
|
|
|
|
|
|
} break;
|
|
|
|
|
|
|
|
|
|
|
|
case TURN_BY_GRAY: //基于灰度传感器
|
|
|
|
|
|
{
|
|
|
|
|
|
//等待一定时间后检测是否摆正
|
|
|
|
|
|
delay(BEFORE_CHECK_STRAIGHT_DELAY);
|
|
|
|
|
|
while (!sensor.IsWhite(GRAY_7)) {}
|
|
|
|
|
|
} break;
|
|
|
|
|
|
|
|
|
|
|
|
case TURN_BY_EARTH: //基于地磁场
|
|
|
|
|
|
{
|
|
|
|
|
|
//等待一定时间后检测是否摆正
|
|
|
|
|
|
delay(BEFORE_CHECK_STRAIGHT_DELAY);
|
|
|
|
|
|
|
|
|
|
|
|
if (direction == FORLEFTWARD || direction == BACKRIGHTWARD)
|
|
|
|
|
|
while (sensor.GetAngle() < next_real_angle) {}
|
|
|
|
|
|
else while (sensor.GetAngle() > next_real_angle) {}
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
current_real_direction = next_real_direction;
|
2021-02-14 12:50:42 +08:00
|
|
|
|
}
|
2021-02-15 12:28:14 +08:00
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出直行或后退或转向结束
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: End Turn Direction");
|
2021-02-15 12:28:14 +08:00
|
|
|
|
#endif
|
2021-02-15 13:14:46 +08:00
|
|
|
|
}
|
2021-02-17 19:35:43 +08:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//抓取环,并判定是否抓取成功
|
2021-03-10 23:41:12 +08:00
|
|
|
|
bool CatchAndCheck(uint8_t type, float speed)
|
2021-02-17 19:35:43 +08:00
|
|
|
|
{
|
2021-02-18 13:19:34 +08:00
|
|
|
|
//记录开始时间
|
|
|
|
|
|
unsigned long begin_time = millis();
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
//抓取延时
|
|
|
|
|
|
int catch_delay_time;
|
|
|
|
|
|
|
2021-02-18 13:19:34 +08:00
|
|
|
|
//抓取次数
|
|
|
|
|
|
uint8_t catch_times = 0;
|
2021-03-10 23:41:12 +08:00
|
|
|
|
|
|
|
|
|
|
if (type == CATCH_TYPE_CATCH)
|
|
|
|
|
|
catch_delay_time = CATCH_DELAY_TIME;
|
|
|
|
|
|
else catch_delay_time = GAINCATCH_DELAY_TIME;
|
2021-02-18 13:19:34 +08:00
|
|
|
|
|
2021-02-17 19:35:43 +08:00
|
|
|
|
//执行抓取动作
|
2021-03-10 23:41:12 +08:00
|
|
|
|
if (type == CATCH_TYPE_CATCH)
|
|
|
|
|
|
servo.Catch(speed);
|
|
|
|
|
|
else servo.GainCatch(speed);
|
2021-02-18 13:19:34 +08:00
|
|
|
|
catch_times++;
|
2021-02-17 19:35:43 +08:00
|
|
|
|
|
|
|
|
|
|
//等待完成动作
|
2021-03-10 23:41:12 +08:00
|
|
|
|
while (millis() - begin_time < catch_delay_time)
|
2021-02-17 19:35:43 +08:00
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#ifndef DISABLE_CLAW_CHECK
|
2021-02-18 13:19:34 +08:00
|
|
|
|
if (sensor.IsPushed(BUTTON_1)) //开关 1 闭合,即爪子两端接触,说明抓取失败
|
2021-02-17 19:35:43 +08:00
|
|
|
|
{
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-02-17 19:56:17 +08:00
|
|
|
|
//调试输出失败信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.print("#TAICHI: **********FAIL CATCH!**********");
|
|
|
|
|
|
NeoSerial.print(" catch_times: "); NeoSerial.println((int)catch_times);
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
if (type == CATCH_TYPE_GAIN)
|
|
|
|
|
|
delay(millis() - begin_time - catch_delay_time); //等待运行完成,防止卡住
|
|
|
|
|
|
|
2021-02-18 13:19:34 +08:00
|
|
|
|
//停止动作组运行
|
|
|
|
|
|
servo.StopActionGroup();
|
|
|
|
|
|
|
2021-03-05 21:56:27 +08:00
|
|
|
|
if (catch_times == MAX_CATCH_TIMES) //达到最大尝试次数,返回
|
|
|
|
|
|
{
|
|
|
|
|
|
servo.Reset();
|
|
|
|
|
|
return false;
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2021-02-18 13:33:55 +08:00
|
|
|
|
//打开爪子
|
|
|
|
|
|
if(!OpenClawAndCheck()) //未能打开爪子
|
2021-02-18 13:19:34 +08:00
|
|
|
|
return false;
|
2021-02-18 21:37:56 +08:00
|
|
|
|
|
|
|
|
|
|
//更新时间
|
|
|
|
|
|
begin_time = millis();
|
|
|
|
|
|
|
|
|
|
|
|
//执行抓取动作
|
2021-03-10 23:41:12 +08:00
|
|
|
|
if (type == CATCH_TYPE_CATCH)
|
|
|
|
|
|
servo.Catch(speed);
|
|
|
|
|
|
else servo.GainCatch(speed);
|
2021-02-18 21:37:56 +08:00
|
|
|
|
catch_times++;
|
2021-02-17 19:35:43 +08:00
|
|
|
|
}
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#endif
|
2021-02-17 19:35:43 +08:00
|
|
|
|
}
|
2021-02-17 19:52:59 +08:00
|
|
|
|
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#ifndef DISABLE_CLAW_CHECK
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#ifdef TAICHI_DEBUG
|
2021-02-17 19:56:17 +08:00
|
|
|
|
//调试输出成功信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: SUCCESS CATCH!");
|
2021-02-17 19:52:59 +08:00
|
|
|
|
#endif
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef DISABLE_CLAW_CHECK
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出结束信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: CATCH WITHOUT CHECK!");
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
#endif
|
2021-02-17 19:52:59 +08:00
|
|
|
|
|
2021-02-18 14:31:51 +08:00
|
|
|
|
is_claw_catch = true;
|
2021-02-17 19:52:59 +08:00
|
|
|
|
return true;
|
2021-02-18 13:33:55 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//打开爪子,并判断爪子是否能正常工作
|
|
|
|
|
|
bool OpenClawAndCheck(void)
|
|
|
|
|
|
{
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#ifdef DISABLE_CLAW_CHECK
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: DISABLE CLAW CHECK!");
|
2021-03-10 23:41:12 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
is_claw_ok = true;
|
|
|
|
|
|
return true;
|
|
|
|
|
|
#endif
|
|
|
|
|
|
|
2021-02-18 13:33:55 +08:00
|
|
|
|
//记录开始时间
|
|
|
|
|
|
unsigned long begin_time = millis();
|
|
|
|
|
|
|
|
|
|
|
|
//打开爪子
|
|
|
|
|
|
servo.OpenClaw();
|
|
|
|
|
|
|
|
|
|
|
|
//等待完成动作
|
|
|
|
|
|
while (millis() - begin_time < CLAW_OPEN_USE_TIME)
|
|
|
|
|
|
{
|
|
|
|
|
|
if (!sensor.IsPushed(BUTTON_1)) //开关 1 打开,即爪子两端脱离接触,说明打开爪子成功
|
|
|
|
|
|
{
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出成功信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: SUCCESS OPEN CLAW!");
|
2021-02-18 13:33:55 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
is_claw_ok = true;
|
|
|
|
|
|
return true;
|
|
|
|
|
|
}
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
#ifdef TAICHI_DEBUG
|
|
|
|
|
|
//调试输出失败信息
|
2021-03-21 23:32:51 +08:00
|
|
|
|
NeoSerial.println("#TAICHI: $$$$$$$$$$FAIL CLAW!$$$$$$$$$$");
|
2021-02-18 13:33:55 +08:00
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
is_claw_ok = false;
|
|
|
|
|
|
return false;
|
2021-03-21 23:32:51 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//通讯消息处理函数
|
|
|
|
|
|
void HandleMessage(char* message)
|
|
|
|
|
|
{
|
|
|
|
|
|
//
|
2021-02-17 19:35:43 +08:00
|
|
|
|
}
|