Compare commits

...

2 Commits

Author SHA1 Message Date
xu
e23808dfac [类型] 加文件注释,飞控消息请求改为部分,飞控通讯的串口2缓冲区加大到2048,怀疑缓冲区小导致放勾指令丢失
详细描述
2025-05-16 19:52:38 +08:00
xu
7a4c95994f [类型] 修改最小重量,加入循环时间检测
详细描述,降低播放延时,日志加入互斥
2025-05-15 19:15:02 +08:00
9 changed files with 59 additions and 10 deletions

View File

@ -1,4 +1,6 @@
#include "FoodDeliveryBase.h"
///MQTT和Mavlink业务逻辑控制
/// @file FoodDeliveryBase.cpp
/**
* @description:
*/
@ -35,7 +37,7 @@ FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int
case 2:
Serial2.begin(57600, SERIAL_8N1);
// 设置接收缓冲区大小为1024字节
Serial2.setRxBufferSize(1024);
Serial2.setRxBufferSize(2048); //飞控用
break;
}
// 初始化声音模块串口 波特率
@ -305,7 +307,7 @@ void FoodCube::playText(String str, VoiceVolume vol)
SWrite(command, sizeof(command), voiceSerial);
// 延时等待模块处理,防止连续播放死机
delay(300); // 可根据模块处理时间调节
//delay(300); // 可根据模块处理时间调节
}
/**
@ -498,9 +500,18 @@ void FoodCube::mav_request_data()
* MAV_DATA_STREAM_ENUM_END=13,
*/
// 根据从Pixhawk请求的所需信息进行设置
const int maxStreams = 1; // 遍历次数 (下面组合的长度)
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_ALL}; // 请求的数据流组合 放到一个对象 后面进行遍历
const uint16_t MAVRates[maxStreams] = {0x01}; // 设定发送频率 分别对应上面数据流 ps:0X01 1赫兹 既每秒发送一次
//const int maxStreams = 1; // 遍历次数 (下面组合的长度)
//const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_ALL}; // 请求的数据流组合 放到一个对象 后面进行遍历
//const uint16_t MAVRates[maxStreams] = {0x01}; // 设定发送频率 分别对应上面数据流 ps:0X01 1赫兹 既每秒发送一次
const int maxStreams = 3;
const uint8_t MAVStreams[maxStreams] = {
MAV_DATA_STREAM_EXTENDED_STATUS,
MAV_DATA_STREAM_POSITION,
MAV_DATA_STREAM_EXTRA1
};
const uint16_t MAVRates[maxStreams] = {1,1,1};
for (int i = 0; i < maxStreams; i++)
{
// 向飞控发送请求

View File

@ -1,3 +1,8 @@
///加入和上层控制器协议解析,可收命令和发送命令返回 ---以前用于和飞控通讯目前已废弃改用mavlink
///使用commser.cpp里面封装的mavlink协议通讯,
///这个库用Serial2目前Serial2用来播放语音
/// @file Serialcommand.cpp
#include "Serialcommand.h"
#include "Arduino.h"
#include "CRC.h"

View File

@ -1,3 +1,6 @@
///Can通讯硬件抽象层给电机控制提供底层can通讯库的封装可兼容不同can通讯库
/// @file can_control.cpp
#include "can_control.h"
#include "Arduino.h"
#include "config.h"

View File

@ -1,3 +1,6 @@
///MQTT以及Mavlink通讯控制
#include "commser.h"
#include "motocontrol.h"
@ -62,7 +65,7 @@ String topicHandle[] = {"crosFrequency"};
Ticker pubTicker; // 定时发布主题 线程
Ticker mavTicker; // 定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后
// Ticker chanTicker; //定时向飞控 发送油门指定
portMUX_TYPE espMutex = portMUX_INITIALIZER_UNLOCKED;
/**
* @description: mqtt订阅主题
* @param {char*} topic msg/macadd
@ -477,7 +480,7 @@ void mavlink_receiveCallback(uint8_t c)
// 没有激光高度直接退出
if (rngalt_cm == 0)
{
rngalt_cm == 500;
//rngalt_cm == 500;
// printf("exit rngalt_cm==0");
addLogMessage("exit rngalt_cm==0激光高度异常");
// break;
@ -985,6 +988,8 @@ void pubThread()
// 添加日志 到日志队列
void addLogMessage(const String &msg)
{
portENTER_CRITICAL(&espMutex);
int nextTail = (logTail + 1) % LOG_QUEUE_SIZE;
if (nextTail != logHead)
{ // 队列未满
@ -996,6 +1001,7 @@ void addLogMessage(const String &msg)
// 队列已满,这里可以选择丢弃或覆盖最旧的日志
// logHead = (logHead + 1) % LOG_QUEUE_SIZE; // 开启这行表示覆盖最旧的
}
portEXIT_CRITICAL(&espMutex);
}
/**

View File

@ -29,7 +29,7 @@
// Moto-CAN //第二版本硬件参数---2号机使用
#define MOTO_CAN_RX 27 // PCB画板需要做了调整
#define MOTO_CAN_TX 26 // PCB画板需要做了调整
#define WEIGHT_SCALE 41 // 减少零点漂移用B通道是41
#define WEIGHT_SCALE 49 // 减少零点漂移用B通道是41 实测改为49
#define HX711_GAIN 32 // 减少零点漂移用B通道的感度
#endif

View File

@ -1,3 +1,5 @@
///主程序,硬件及线程控制
/// @file main.cpp
#include <Arduino.h>
#include "HX711.h"
#include "OneButton.h"
@ -74,6 +76,13 @@ bool _checkweightcal = false; // 检测是否要检测称重传感器是否需
uint8_t _checkweighttimes = 0; //
unsigned long _tm_checkweigh;
static const char *MOUDLENAME = "MAIN";
unsigned long _tm_core1 ; //主核心1 循环开始时间
unsigned long _tm_core0 ; //核心0 循环开始时间
unsigned long _looptm_core1=0 ; //主核心1单次循环时间--评估是否超时卡顿
unsigned long _looptm_core0=0 ; //核心0单次循环时间--评估是否超时卡顿
// 称重校准状态
enum Weightalign_status
{
@ -147,7 +156,7 @@ void setup()
fc.mqttClient->setCallback(mqtt_receiveCallback); // 设置订阅成功 回调
fc.mav_request_data(); // 指定飞控串口返回的数据类别(飞控启动之后发送才有意义)
/*异步线程*/
/*异步线程在核心0上回调*/
tksendinfo.attach(1, sendinfo); // 发送状态
pubTicker.attach(1, pubThread); // 定时 发布主题
/////////////////////////////////MQTT_语音_MAVLINK 部分结束
@ -407,6 +416,7 @@ void set_locked(bool locked)
// 在核心1上执行重要的延迟低的
void loop()
{
_tm_core1= millis();
// sercomm.getcommand(); // 得到控制命令
button_checktop.tick(); // 按钮
button_down.tick(); // 按钮
@ -441,6 +451,15 @@ void loop()
check_tare(); // 检查看是否需要校准称重
checkinited(); // 检测执行初始化工作
delay(1);
_looptm_core1= millis()-_tm_core1;
//如果循环时间超过1000ms,则打印错误日志
//if (_looptm_core1>1000)
{
// ESP_LOGE(MOUDLENAME, "main loop time out %d ms", _looptm_core1);
addLogMessage("core1 loop time out: " + String(_looptm_core1));
}
}
// 在核心0上执行耗时长的低优先级的
void Task1(void *pvParameters)

View File

@ -1,3 +1,5 @@
///DJI电机控制协议及基础控制层通过Can总线控制电机,依赖于CAN硬件抽象层
// /// @file moto.cpp
#include "moto.h"
#include "Arduino.h"
#include "config.h"

View File

@ -1,3 +1,6 @@
/// 电机控制业务逻辑封装-依赖moto类
/// @file motocontrol.cpp
#include "Arduino.h"
#include "motocontrol.h"

View File

@ -34,7 +34,7 @@
#define SERVO_UNLOCKPOS 1120 // 1800 // 舵机解锁位置
#define SERVO_BLOCKUNLOCKPOS 1100 // 舵机堵转需要转回的位置--可以和SERVO_UNLOCKPOS一样为了速度快也可以更小
#define HOOK_WEIHT_MIN 100 // 最小货物重量 小于这个认为没挂东西 (克)
#define HOOK_WEIHT_MIN 300 // 最小货物重量 小于这个认为没挂东西 (克)
#define HOOK_WEIHT_MAX 12000 // 最大货物重量 大于这个认为超重不工作 (克)