GCS_MAVLink: add support for send_mission_item_reached

This commit is contained in:
Randy Mackay 2015-07-18 14:25:12 +09:00
parent c5550329a3
commit a61129f7f8
2 changed files with 9 additions and 0 deletions

View File

@ -141,6 +141,7 @@ public:
void send_autopilot_version(void) const;
void send_local_position(const AP_AHRS &ahrs) const;
void send_vibration(const AP_InertialSensor &ins) const;
void send_mission_item_reached(uint16_t seq) const;
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels

View File

@ -1336,3 +1336,11 @@ void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const
ins.get_accel_clip_count(2));
#endif
}
/*
* send notification that a mission command has been completed
*/
void GCS_MAVLINK::send_mission_item_reached(uint16_t seq) const
{
mavlink_msg_mission_item_reached_send(chan, seq);
}