AP_Mission: Decode MAV_CMD_DO_PAUSE_CONTINUE commands

This commit is contained in:
m 2021-11-24 13:46:40 +03:00 committed by Randy Mackay
parent e8677216b6
commit c729fc7796
2 changed files with 12 additions and 1 deletions

View File

@ -1170,6 +1170,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
cmd.content.nav_script_time.arg1 = packet.param3;
cmd.content.nav_script_time.arg2 = packet.param4;
break;
case MAV_CMD_DO_PAUSE_CONTINUE:
cmd.p1 = packet.param1;
break;
default:
// unrecognised command
@ -1629,6 +1633,10 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
packet.param3 = cmd.content.nav_script_time.arg1;
packet.param4 = cmd.content.nav_script_time.arg2;
break;
case MAV_CMD_DO_PAUSE_CONTINUE:
packet.param1 = cmd.p1;
break;
default:
// unrecognised command
@ -2350,6 +2358,8 @@ const char *AP_Mission::Mission_Command::type() const
return "Go Around";
case MAV_CMD_NAV_SCRIPT_TIME:
return "NavScriptTime";
case MAV_CMD_DO_PAUSE_CONTINUE:
return "PauseContinue";
default:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -604,6 +604,8 @@ protected:
*/
uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size);
static void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
private:
// last time we got a non-zero RSSI from RADIO_STATUS
@ -624,7 +626,6 @@ private:
MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
static bool command_long_stores_location(const MAV_CMD command);
static void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
bool calibrate_gyros();