【类 型】:factor 不记录飞机状态 改用 直接控制飞机 起飞 降落等 (未完成)
【原 因】: 【过 程】: 【影 响】:
This commit is contained in:
parent
93e5071c95
commit
b641bf4381
@ -122,35 +122,10 @@ IPAddress secondaryDNS(8, 8, 4, 4); // optional
|
||||
|
||||
void FoodCube::connectWifi()
|
||||
{
|
||||
|
||||
// if (!WiFi.config(local_IP, gateway, subnet, primaryDNS, secondaryDNS)) {
|
||||
// ESP_LOGD(MOUDLENAME,"STA Failed to configure");
|
||||
// }
|
||||
|
||||
// 设置wifi帐号密码
|
||||
WiFi.begin(ssid, password);
|
||||
// 连接wifi
|
||||
logln("Connecting Wifi...");
|
||||
/*
|
||||
while (WiFi.status() != WL_CONNECTED) {
|
||||
log(".");
|
||||
delay(150);
|
||||
}
|
||||
//获取局域网ip
|
||||
logln("");
|
||||
logln("WiFi connected");
|
||||
log("IP address: ");
|
||||
logln(WiFi.localIP());
|
||||
localIp = WiFi.localIP();
|
||||
//设置开发板为无线终端 获取物理mac地址
|
||||
WiFi.mode(WIFI_STA);
|
||||
macAdd = WiFi.macAddress();
|
||||
macAdd.replace(":", ""); //板子的物理地址 并且去除冒号
|
||||
log("macAdd: ");
|
||||
logln(macAdd);
|
||||
playText("网络连接成功");
|
||||
delay(500);
|
||||
*/
|
||||
}
|
||||
|
||||
bool FoodCube::checkWiFiStatus()
|
||||
@ -706,15 +681,7 @@ void FoodCube::mav_set_mode(uint8_t SysState)
|
||||
// 通过串口发送
|
||||
SWrite(buf, len, mavlinkSerial);
|
||||
}
|
||||
void FoodCube::mav_send_command(mavlink_command_long_t msg_cmd)
|
||||
{
|
||||
mavlink_message_t msg; // mavlink协议信息(msg)
|
||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
|
||||
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &msg_cmd);
|
||||
int len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
// 通过串口发送
|
||||
SWrite(buf, len, mavlinkSerial);
|
||||
}
|
||||
|
||||
void FoodCube::mav_send_text(uint8_t severity, const char *text)
|
||||
{
|
||||
return;
|
||||
@ -769,18 +736,6 @@ void FoodCube::mav_command(uint8_t controlType, uint16_t param[])
|
||||
{ // 降落
|
||||
cmd.command = MAV_CMD_NAV_LAND;
|
||||
}
|
||||
else if (controlType == 11)
|
||||
{
|
||||
// 磁罗盘校准
|
||||
cmd.command = MAV_CMD_DO_START_MAG_CAL;
|
||||
cmd.param1 = 0; // 磁罗盘的bitmask(0表示所有)
|
||||
cmd.param2 = 1; // 自动重试(0=不重试, 1=重试)
|
||||
cmd.param3 = 0; // 是否自动保存(0=需要用户输入, 1=自动保存)
|
||||
cmd.param4 = 0; // 延迟(秒)
|
||||
cmd.param5 = 0; // 自动重启(0=用户重启, 1=自动重启)
|
||||
cmd.param6 = 0; // 保留空参数
|
||||
cmd.param7 = 0; // 保留空参数
|
||||
}
|
||||
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &cmd);
|
||||
int len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
// 通过串口发送
|
||||
@ -800,3 +755,13 @@ void FoodCube::mav_channels_override(uint16_t chan[])
|
||||
// 通过串口发送
|
||||
SWrite(buf, len, mavlinkSerial);
|
||||
}
|
||||
|
||||
void FoodCube::mav_send_command(mavlink_command_long_t msg_cmd)
|
||||
{
|
||||
mavlink_message_t msg; // mavlink协议信息(msg)
|
||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // 发送的缓存
|
||||
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &msg_cmd);
|
||||
int len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
// 通过串口发送
|
||||
SWrite(buf, len, mavlinkSerial);
|
||||
}
|
||||
|
@ -84,18 +84,12 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
|
||||
/*
|
||||
*其中topicPubMsg[10]既飞机状态的值
|
||||
*二进制0000 0000 0000 0000
|
||||
*第0位: 初始状态 &1
|
||||
*第0位: 初始状态 &1
|
||||
*第1位: 正在写入航线 &2
|
||||
*第2位: 已经写入航点 &4
|
||||
*第3位: 正在解锁 &8
|
||||
*第4位: 解锁成功 &16
|
||||
*第5位: 执行航点任务 &32
|
||||
*第6位: 起飞 &64
|
||||
*第7位: 悬停 &128
|
||||
*第8位: 降落 &256
|
||||
*第9位: 返航 &512
|
||||
*第10位:航点继续 &1024
|
||||
*第11位:磁罗盘校准 &2048
|
||||
*第3位: 正在解锁 &8
|
||||
*第4位: 解锁成功 &16
|
||||
*第5位: 执行航点任务 &32
|
||||
*/
|
||||
String todoJson = value; // 转换值
|
||||
/* json 反序列化 */
|
||||
@ -131,31 +125,62 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
|
||||
fc.mav_set_mode(4); // 飞控设置成Guided引导模式
|
||||
fc.mav_command(n, param); // 起飞
|
||||
}
|
||||
else if (n == 7)
|
||||
{ // 7 悬停
|
||||
fc.mav_set_mode(5); // 飞控设置成Loiter留待模式
|
||||
}
|
||||
else if (n == 5)
|
||||
{ // 5 航点执行
|
||||
fc.mav_set_mode(3); // 飞控设置成auto自动模式
|
||||
}
|
||||
else if (n == 8) // 8降落
|
||||
{
|
||||
fc.mav_command(n, param);
|
||||
}
|
||||
else if (n == 9)
|
||||
{ // 9返航
|
||||
fc.mav_set_mode(6); // 飞控设置成RTL返航
|
||||
}
|
||||
else if (n == 11) // 11磁罗盘校准
|
||||
{
|
||||
/*初始化磁罗盘校准进度 和 校准结果*/
|
||||
topicPubMsg[8] = "";
|
||||
topicPubMsg[9] = "";
|
||||
/*校准*/
|
||||
fc.mav_command(n, param);
|
||||
fc.playText("校准磁罗盘");
|
||||
}
|
||||
}
|
||||
else if (key == "autoMode")
|
||||
{ // 自动模式
|
||||
mavlink_command_long_t msg_cmd; // 命令结构体
|
||||
memset(&msg_cmd, 0, sizeof(msg_cmd)); // 初始化为0
|
||||
msg_cmd.command = MAV_CMD_NAV_WAYPOINT; // 使用适当的命令,这里示例用 MAV_CMD_NAV_WAYPOINT 代替自动模式
|
||||
msg_cmd.param1 = 0; // 根据需要设置其他参数
|
||||
msg_cmd.param2 = 0;
|
||||
msg_cmd.param3 = 0;
|
||||
msg_cmd.param4 = 0;
|
||||
msg_cmd.param5 = 0;
|
||||
msg_cmd.param6 = 0;
|
||||
msg_cmd.param7 = 0;
|
||||
fc.mav_send_command(msg_cmd);
|
||||
}
|
||||
else if (key == "loiterMode")
|
||||
{ // 悬停 既定点
|
||||
mavlink_command_long_t msg_cmd; // 命令结构体
|
||||
memset(&msg_cmd, 0, sizeof(msg_cmd)); // 初始化为0
|
||||
msg_cmd.command = MAV_CMD_NAV_LOITER_TURNS; // 设置为悬停命令
|
||||
msg_cmd.param1 = 0; // 可选参数1 (具体值取决于命令的要求)
|
||||
msg_cmd.param2 = 0; // 可选参数2 (具体值取决于命令的要求)
|
||||
msg_cmd.param3 = 0; // 可选参数3 (具体值取决于命令的要求)
|
||||
msg_cmd.param4 = 0; // 可选参数4 (具体值取决于命令的要求)
|
||||
msg_cmd.param5 = 0; // 可选参数5 (具体值取决于命令的要求)
|
||||
msg_cmd.param6 = 0; // 可选参数6 (具体值取决于命令的要求)
|
||||
msg_cmd.param7 = 0; // 可选参数7 (具体值取决于命令的要求)
|
||||
fc.mav_send_command(msg_cmd); // 发送悬停命令
|
||||
}
|
||||
else if (key == "landMode")
|
||||
{ // 降落
|
||||
mavlink_command_long_t msg_cmd; // 命令结构体
|
||||
memset(&msg_cmd, 0, sizeof(msg_cmd)); // 初始化为0
|
||||
msg_cmd.command = MAV_CMD_NAV_LAND; // 设置为降落命令
|
||||
fc.mav_send_command(msg_cmd); // 发送降落命令
|
||||
}
|
||||
else if (key == "rtlMode")
|
||||
{ // 返航
|
||||
mavlink_command_long_t msg_cmd; // 命令结构体
|
||||
memset(&msg_cmd, 0, sizeof(msg_cmd)); // 初始化为0
|
||||
msg_cmd.command = MAV_CMD_NAV_RETURN_TO_LAUNCH; // #20 设置为返航命令
|
||||
fc.mav_send_command(msg_cmd); // 发送返航命令
|
||||
}
|
||||
else if (key == "resetCompass")
|
||||
{ // 校准磁罗盘
|
||||
mavlink_command_long_t msg_cmd; // 命令结构体
|
||||
memset(&msg_cmd, 0, sizeof(msg_cmd)); // 初始化为0
|
||||
msg_cmd.command = MAV_CMD_DO_START_MAG_CAL; // #42424 校准磁罗盘
|
||||
msg_cmd.param1 = 0; // 磁罗盘的bitmask(0表示所有)
|
||||
msg_cmd.param2 = 1; // 自动重试(0=不重试, 1=重试)
|
||||
msg_cmd.param3 = 0; // 是否自动保存(0=需要用户输入, 1=自动保存)
|
||||
msg_cmd.param4 = 0; // 延迟(秒)
|
||||
msg_cmd.param5 = 0; // 自动重启(0=用户重启, 1=自动重启)
|
||||
msg_cmd.param6 = 0; // 保留空参数
|
||||
msg_cmd.param7 = 0; // 保留空参数
|
||||
fc.mav_send_command(msg_cmd);
|
||||
}
|
||||
else if (key == "refreshRequest")
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user