mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: move common mission handling up to GCS_MAVLINK
This commit is contained in:
parent
9f73d2f9d8
commit
3660236a0d
@ -880,64 +880,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
|
||||
{
|
||||
handle_mission_write_partial_list(copter.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
// GCS has sent us a mission item, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
|
||||
{
|
||||
if (handle_mission_item(msg, copter.mission)) {
|
||||
copter.DataFlash.Log_Write_EntireMission(copter.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
|
||||
{
|
||||
if (handle_mission_item(msg, copter.mission)) {
|
||||
copter.DataFlash.Log_Write_EntireMission(copter.mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// read an individual command from EEPROM and send it to the GCS
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40, 51
|
||||
{
|
||||
handle_mission_request(copter.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
|
||||
{
|
||||
handle_mission_set_current(copter.mission, 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: // MAV ID: 43
|
||||
{
|
||||
handle_mission_request_list(copter.mission, msg);
|
||||
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: // MAV ID: 44
|
||||
{
|
||||
handle_mission_count(copter.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: // MAV ID: 45
|
||||
{
|
||||
handle_mission_clear_all(copter.mission, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: // MAV ID: 66
|
||||
{
|
||||
handle_request_data_stream(msg, false);
|
||||
@ -2075,3 +2017,8 @@ bool GCS_MAVLINK_Copter::accept_packet(const mavlink_status_t &status, mavlink_m
|
||||
}
|
||||
return (msg.sysid == copter.g.sysid_my_gcs);
|
||||
}
|
||||
|
||||
AP_Mission *GCS_MAVLINK_Copter::get_mission()
|
||||
{
|
||||
return &copter.mission;
|
||||
}
|
||||
|
@ -17,7 +17,9 @@ 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;
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
|
Loading…
Reference in New Issue
Block a user