MAVLink: use enum ap_message and remove unused param argument

saves us another 200 bytes of text
This commit is contained in:
Andrew Tridgell 2011-09-18 13:39:33 +10:00
parent 9fed709be2
commit 83492f92f2
3 changed files with 6 additions and 6 deletions

View File

@ -56,7 +56,7 @@ public:
/// @param id ID of the message to send.
/// @param param Explicit message parameter.
///
void send_message(uint8_t id, int32_t param = 0) {}
void send_message(enum ap_message id) {}
/// Send a text message.
///
@ -140,7 +140,7 @@ public:
GCS_MAVLINK(AP_Var::Key key);
void update(void);
void init(FastSerial *port);
void send_message(uint8_t id, uint32_t param = 0);
void send_message(enum ap_message id);
void send_text(uint8_t severity, const char *str);
void send_text(uint8_t severity, const prog_char_t *str);
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);

View File

@ -139,7 +139,7 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
}
void
GCS_MAVLINK::send_message(uint8_t id, uint32_t param)
GCS_MAVLINK::send_message(enum ap_message id)
{
mavlink_send_message(chan,id, packet_drops);
}

View File

@ -291,7 +291,7 @@ static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
// try to send a message, return false if it won't fit in the serial tx buffer
static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_t packet_drops)
static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{
int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
@ -395,13 +395,13 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
#define MAX_DEFERRED_MESSAGES MSG_RETRY_DEFERRED
static struct mavlink_queue {
uint8_t deferred_messages[MAX_DEFERRED_MESSAGES];
enum ap_message deferred_messages[MAX_DEFERRED_MESSAGES];
uint8_t next_deferred_message;
uint8_t num_deferred_messages;
} mavlink_queue[2];
// send a message using mavlink
static void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint16_t packet_drops)
static void mavlink_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{
uint8_t i, nextid;
struct mavlink_queue *q = &mavlink_queue[(uint8_t)chan];