GCS: simplify the API for sending messages

this makes the code clearer, and saves us another 100 bytes of text
This commit is contained in:
Andrew Tridgell 2011-09-18 13:46:42 +10:00
parent 83492f92f2
commit 35fcd6dae7
4 changed files with 33 additions and 35 deletions

View File

@ -461,8 +461,7 @@ static void fast_loop()
// try to send any deferred messages if the serial port now has
// some space available
gcs.send_message(MSG_RETRY_DEFERRED);
hil.send_message(MSG_RETRY_DEFERRED);
gcs_send_message(MSG_RETRY_DEFERRED);
// check for loss of control signal failsafe condition
// ------------------------------------
@ -519,8 +518,7 @@ static void fast_loop()
gcs.update();
hil.update();
gcs.data_stream_send(45,1000);
hil.data_stream_send(45,1000);
gcs_data_stream_send(45,1000);
}
static void medium_loop()
@ -613,8 +611,7 @@ Serial.println(tempaccel.z, DEC);
// send all requested output streams with rates requested
// between 5 and 45 Hz
gcs.data_stream_send(5,45);
hil.data_stream_send(5,45);
gcs_data_stream_send(5,45);
break;
// This case controls the slow loop
@ -673,8 +670,7 @@ static void slow_loop()
update_events();
mavlink_system.sysid = g.sysid_this_mav; // This is just an ugly hack to keep mavlink_system.sysid sync'd with our parameter
gcs.data_stream_send(3,5);
hil.data_stream_send(3,5);
gcs_data_stream_send(3,5);
break;
}
}
@ -685,10 +681,8 @@ static void one_second_loop()
Log_Write_Current();
// send a heartbeat
gcs.send_message(MSG_HEARTBEAT);
hil.send_message(MSG_HEARTBEAT);
gcs.data_stream_send(1,3);
hil.data_stream_send(1,3);
gcs_send_message(MSG_HEARTBEAT);
gcs_data_stream_send(1,3);
}
static void update_GPS(void)
@ -697,13 +691,6 @@ static void update_GPS(void)
update_GPS_light();
if (g_gps->new_data && g_gps->fix) {
// XXX We should be sending GPS data off one of the regular loops so that we send
// no-GPS-fix data too
#if GCS_PROTOCOL != GCS_PROTOCOL_MAVLINK
gcs.send_message(MSG_LOCATION);
#endif
// for performance
// ---------------
gps_fix_count++;

View File

@ -1110,10 +1110,8 @@ static void mavlink_delay(unsigned long t)
unsigned long tnow = millis();
if (tnow - last_1hz > 1000) {
last_1hz = tnow;
gcs.send_message(MSG_HEARTBEAT);
hil.send_message(MSG_HEARTBEAT);
gcs.send_message(MSG_EXTENDED_STATUS1);
hil.send_message(MSG_EXTENDED_STATUS1);
gcs_send_message(MSG_HEARTBEAT);
gcs_send_message(MSG_EXTENDED_STATUS1);
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
@ -1125,3 +1123,21 @@ static void mavlink_delay(unsigned long t)
in_mavlink_delay = false;
}
/*
send a message on both GCS links
*/
static void gcs_send_message(enum ap_message id)
{
gcs.send_message(id);
hil.send_message(id);
}
/*
send data streams in the given rate range on both links
*/
static void gcs_data_stream_send(uint16_t freqMin, uint16_t freqMax)
{
gcs.data_stream_send(freqMin, freqMax);
hil.data_stream_send(freqMin, freqMax);
}

View File

@ -206,9 +206,6 @@ static void do_RTL(void)
// -------------------------
next_WP.alt = read_alt_to_hold();
// output control mode to the ground station
gcs.send_message(MSG_HEARTBEAT);
if (g.log_bitmask & MASK_LOG_MODE)
Log_Write_Mode(control_mode);
}

View File

@ -33,15 +33,13 @@ planner_gcs(uint8_t argc, const Menu::arg *argv)
fast_loopTimer = millis();
gcs.update();
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
gcs.data_stream_send(45,1000);
if ((loopcount % 5) == 0) // 10 hz
gcs.data_stream_send(5,45);
if ((loopcount % 16) == 0) { // 3 hz
gcs.data_stream_send(1,5);
gcs.send_message(MSG_HEARTBEAT);
}
#endif
gcs_data_stream_send(45,1000);
if ((loopcount % 5) == 0) // 10 hz
gcs_data_stream_send(5,45);
if ((loopcount % 16) == 0) { // 3 hz
gcs_data_stream_send(1,5);
gcs_send_message(MSG_HEARTBEAT);
}
loopcount++;
}
}