mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: move common mission handling up to GCS_MAVLINK
This commit is contained in:
parent
726007efde
commit
d850feb75f
@ -1567,28 +1567,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
|
||||
{
|
||||
handle_mission_request_list(plane.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
// XXX read a WP from EEPROM and send it to the GCS
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST:
|
||||
{
|
||||
handle_mission_request(plane.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_ACK:
|
||||
{
|
||||
// nothing to do
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
// mark the firmware version in the tlog
|
||||
@ -1601,56 +1579,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
|
||||
{
|
||||
handle_mission_clear_all(plane.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
|
||||
{
|
||||
// disable cross-track when user asks for WP change, to
|
||||
// prevent unexpected flight paths
|
||||
plane.auto_state.next_wp_no_crosstrack = true;
|
||||
handle_mission_set_current(plane.mission, msg);
|
||||
if (plane.control_mode == AUTO && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
|
||||
plane.mission.resume();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS provides the full number of commands it wishes to upload
|
||||
// individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
|
||||
case MAVLINK_MSG_ID_MISSION_COUNT:
|
||||
{
|
||||
handle_mission_count(plane.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
||||
{
|
||||
handle_mission_write_partial_list(plane.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS has sent us a mission item, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM:
|
||||
{
|
||||
if (handle_mission_item(msg, plane.mission)) {
|
||||
plane.DataFlash.Log_Write_EntireMission(plane.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS has sent us a mission item, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
|
||||
{
|
||||
if (handle_mission_item(msg, plane.mission)) {
|
||||
plane.DataFlash.Log_Write_EntireMission(plane.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
// receive a fence point from GCS and store in EEPROM
|
||||
case MAVLINK_MSG_ID_FENCE_POINT: {
|
||||
@ -2180,3 +2108,17 @@ bool GCS_MAVLINK_Plane::accept_packet(const mavlink_status_t &status, mavlink_me
|
||||
}
|
||||
return (msg.sysid == plane.g.sysid_my_gcs);
|
||||
}
|
||||
|
||||
AP_Mission *GCS_MAVLINK_Plane::get_mission()
|
||||
{
|
||||
return &plane.mission;
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
|
||||
{
|
||||
plane.auto_state.next_wp_no_crosstrack = true;
|
||||
GCS_MAVLINK::handle_mission_set_current(mission, msg);
|
||||
if (plane.control_mode == AUTO && plane.mission.state() == AP_Mission::MISSION_STOPPED) {
|
||||
plane.mission.resume();
|
||||
}
|
||||
}
|
||||
|
@ -17,7 +17,10 @@ protected:
|
||||
uint32_t telem_delay() const override;
|
||||
|
||||
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
||||
|
||||
|
||||
AP_Mission *get_mission() override;
|
||||
void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override;
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
|
Loading…
Reference in New Issue
Block a user