mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter: move try_send_message mission handling up
This commit is contained in:
parent
3b472ccc17
commit
3e5665735f
@ -708,7 +708,6 @@ private:
|
|||||||
void send_simstate(mavlink_channel_t chan);
|
void send_simstate(mavlink_channel_t chan);
|
||||||
void send_hwstatus(mavlink_channel_t chan);
|
void send_hwstatus(mavlink_channel_t chan);
|
||||||
void send_vfr_hud(mavlink_channel_t chan);
|
void send_vfr_hud(mavlink_channel_t chan);
|
||||||
void send_current_waypoint(mavlink_channel_t chan);
|
|
||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void button_update();
|
void button_update();
|
||||||
|
@ -202,11 +202,6 @@ void NOINLINE Copter::send_vfr_hud(mavlink_channel_t chan)
|
|||||||
climb_rate / 100.0f);
|
climb_rate / 100.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
void NOINLINE Copter::send_current_waypoint(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
send RPM packet
|
send RPM packet
|
||||||
*/
|
*/
|
||||||
@ -393,21 +388,11 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||||||
send_sensor_offsets(copter.ins, copter.compass, copter.barometer);
|
send_sensor_offsets(copter.ins, copter.compass, copter.barometer);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_CURRENT_WAYPOINT:
|
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
|
||||||
copter.send_current_waypoint(chan);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_NEXT_PARAM:
|
case MSG_NEXT_PARAM:
|
||||||
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
||||||
queued_param_send();
|
queued_param_send();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_NEXT_WAYPOINT:
|
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
|
||||||
queued_waypoint_send();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_RANGEFINDER:
|
case MSG_RANGEFINDER:
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||||
@ -515,11 +500,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||||||
send_vibration(copter.ins);
|
send_vibration(copter.ins);
|
||||||
break;
|
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:
|
case MSG_ADSB_VEHICLE:
|
||||||
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||||
copter.adsb.send_adsb_vehicle(chan);
|
copter.adsb.send_adsb_vehicle(chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user