GCS_MAVLink: add support for try send mission_item_reached

also moved most of send_item_reached into common library
This commit is contained in:
Tom Pittenger 2015-07-24 00:18:14 -07:00 committed by Randy Mackay
parent 9c75900746
commit 7b611f8e26
2 changed files with 9 additions and 8 deletions

View File

@ -18,6 +18,11 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Mount/AP_Mount.h>
// check if a message will fit in the payload space available
#define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_ ## id ## _LEN)
#define CHECK_PAYLOAD_SIZE(id) if (comm_get_txspace(chan) < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_ ## id ## _LEN) return false
#define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
// GCS Message ID's
/// NOTE: to ensure we never block on sending MAVLink messages
/// please keep each MSG_ to a single MAVLink message. If need be
@ -61,6 +66,7 @@ enum ap_message {
MSG_PID_TUNING,
MSG_VIBRATION,
MSG_RPM,
MSG_MISSION_ITEM_REACHED,
MSG_RETRY_DEFERRED // this must be last
};
@ -124,6 +130,9 @@ public:
// last time we got a non-zero RSSI from RADIO_STATUS
static uint32_t last_radio_status_remrssi_ms;
// mission item index to be sent on queued msg, delayed or not
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
// common send functions
void send_meminfo(void);
void send_power_status(void);
@ -142,7 +151,6 @@ public:
void send_autopilot_version() 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

@ -1353,10 +1353,3 @@ void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const
#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);
}