mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: move try_send_message mission handling up
This commit is contained in:
parent
3e5665735f
commit
fee9e83881
@ -414,11 +414,6 @@ void Plane::send_pid_tuning(mavlink_channel_t chan)
|
||||
}
|
||||
}
|
||||
|
||||
void Plane::send_current_waypoint(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
|
||||
}
|
||||
|
||||
uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const
|
||||
{
|
||||
return plane.g.sysid_my_gcs;
|
||||
@ -545,21 +540,11 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
send_sensor_offsets(plane.ins, plane.compass, plane.barometer);
|
||||
break;
|
||||
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
||||
plane.send_current_waypoint(chan);
|
||||
break;
|
||||
|
||||
case MSG_NEXT_PARAM:
|
||||
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
||||
queued_param_send();
|
||||
break;
|
||||
|
||||
case MSG_NEXT_WAYPOINT:
|
||||
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
||||
queued_waypoint_send();
|
||||
break;
|
||||
|
||||
case MSG_FENCE_STATUS:
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
||||
@ -660,11 +645,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
plane.send_rpm(chan);
|
||||
break;
|
||||
|
||||
case MSG_MISSION_ITEM_REACHED:
|
||||
CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
|
||||
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
||||
break;
|
||||
|
||||
case MSG_ADSB_VEHICLE:
|
||||
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||
plane.adsb.send_adsb_vehicle(chan);
|
||||
|
@ -817,7 +817,6 @@ private:
|
||||
void send_wind(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void send_current_waypoint(mavlink_channel_t chan);
|
||||
|
||||
void send_aoa_ssa(mavlink_channel_t chan);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user