Copter: handle MISSION_START as both COMMAND_LONG and COMMAND_INT

This commit is contained in:
Peter Barker 2023-09-19 17:26:22 +10:00 committed by Peter Barker
parent 4a15d9cc1b
commit b3dd5c20c5
2 changed files with 16 additions and 5 deletions

View File

@ -776,6 +776,11 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet); return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet);
#endif #endif
#if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_MISSION_START:
return handle_MAV_CMD_MISSION_START(packet);
#endif
#if AP_WINCH_ENABLED #if AP_WINCH_ENABLED
case MAV_CMD_DO_WINCH: case MAV_CMD_DO_WINCH:
return handle_MAV_CMD_DO_WINCH(packet); return handle_MAV_CMD_DO_WINCH(packet);
@ -893,8 +898,14 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
} }
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}
#if MODE_AUTO_ENABLED == ENABLED #if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_MISSION_START: MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
{
if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) { if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
copter.set_auto_armed(true); copter.set_auto_armed(true);
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) { if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {
@ -903,12 +914,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;
} }
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
}
#endif #endif
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)

View File

@ -107,6 +107,8 @@ private:
MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet);
#endif #endif
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
#if AP_WINCH_ENABLED #if AP_WINCH_ENABLED
MAV_RESULT handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet);
#endif #endif