#pragma once //////////// // 定义公共结构,变量,硬件接口等 /// // #define VERSION "0.90" // 软件版本 #define VERSION_HW 2 // 硬件版本1:第一块硬件 2:目前版本 // 硬件接口定义//////////////////////////// // 按钮 #define BTN_UP 23 // 收线开关 接线:BTN_UP---GND #define BTN_DOWN 22 // 放线开关 #define BTN_CT 21 // 到顶检测开关 #define BTN_TEST 18 // 测试开关 // 称重传感器- HX711 #define LOADCELL_DOUT_PIN 13 // 16 #define LOADCELL_SCK_PIN 33 // 17 /////////////////////////////////////////// #define SERVO_PIN 14 // 锁定舵机PWM控制脚 ////LED #define LED_DATA_PIN 25 #if (VERSION_HW == 1) // Moto-CAN //第一版本硬件参数---1号机使用 #define MOTO_CAN_RX 26 #define MOTO_CAN_TX 27 #define WEIGHT_SCALE 165 // //A通道是165,B通道是41 #define HX711_GAIN 128 #else // Moto-CAN //第二版本硬件参数---2号机使用 #define MOTO_CAN_RX 27 // PCB画板需要,做了调整 #define MOTO_CAN_TX 26 // PCB画板需要,做了调整 #define WEIGHT_SCALE 41 // 减少零点漂移用B通道是41 #define HX711_GAIN 32 // 减少零点漂移用B通道的感度 #endif /// serial1 #define SERIAL_REPORT_TX 5 #define SERIAL_REPORT_RX 18 ///// // #define WEIGHT_SCALE 41 // //A通道是165,B通道是41 #define TM_INSTORE_WEIGHT_DELAY 200 // 200 // 入仓动力延时关闭时间 ms #define TM_INSTORE_DELAY_WEIGHT 200 // 入仓动力延时关闭时间生效的重量(g),免得空钩也延时关闭导致线拉紧 ms #define TM_INSTORE_NOWEIGHT_DELAY 50 // 空钩完全不延时也可能顶部按键按不下去,加一点延时 ms enum HookStatus { HS_UnInit, // 还未初始化 HS_Down, // 货物下放中 HS_DownSlow, // 货物慢速下放中 --接近地面慢速,不受设置速度影响 HS_WaitUnhook, // 等待脱钩 HS_Up, // 回收中 HS_InStore, // 入仓中 --慢速,不受设置速度影响 HS_Locked, // 已到顶部锁定 HS_Stop // 已停止 }; enum Initstatus { IS_WaitStart, // 0. 刚上电,等待初始化--顶部按钮按下有延时,需要等一下看看这个按钮是否按下以确定是否需要收线 IS_Start, // 0. 刚上电 IS_Wait_Locked, IS_LengthZero, // 1.已确定零点 IS_begin_WeightZero, IS_Wait_WeightZero, IS_WeightZero, // 2.已确定称重传感器0点 IS_InStoreLocked, // 3. 挂钩入仓顶锁定 IS_CheckWeightZero, // 检查称重传感器是否归0 IS_OK, // 4.所有初始化已经OK,可以正常操作 IS_Error // 5.初始化遇到错误 }; const uint16_t MAV_CMD_FC_HOOK_AUTODOWN = 40; // 飞控发的---自动放线 const uint16_t MAV_CMD_FC_HOOK_PAUSE = 41; // 飞控发的---暂停 const uint16_t MAV_CMD_FC_HOOK_STATUS = 42; // 发给飞控的状态 const uint16_t MAV_CMD_FC_HOOK_RECOVERY = 43; // 飞控发的---收线 const uint16_t MAV_CMD_FC_DESCENTSTART = 44; // 飞开始下降,需要调整相机向下