AntennaTracker: use new GCS_Common.cpp functions

This commit is contained in:
Andrew Tridgell 2014-05-28 09:36:12 +10:00
parent cea30e1d9f
commit 286fdf2acc

View File

@ -101,54 +101,6 @@ static void NOINLINE send_location(mavlink_channel_t chan)
ahrs.yaw_sensor);
}
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{
static uint32_t last_send_time_ms;
if (last_send_time_ms == 0 || last_send_time_ms != gps.last_message_time_ms(0)) {
last_send_time_ms = gps.last_message_time_ms(0);
const Location &loc = gps.location(0);
mavlink_msg_gps_raw_int_send(
chan,
gps.last_fix_time_ms(0)*(uint64_t)1000,
gps.status(0),
loc.lat, // in 1E7 degrees
loc.lng, // in 1E7 degrees
loc.alt * 10UL, // in mm
gps.get_hdop(0),
65535,
gps.ground_speed(0)*100, // cm/s
gps.ground_course_cd(0), // 1/100 degrees,
gps.num_sats(0));
}
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
static uint32_t last_send_time_ms2;
if (gps.num_sensors() > 1 &&
gps.status(1) > AP_GPS::NO_GPS &&
(last_send_time_ms2 == 0 || last_send_time_ms2 != gps.last_message_time_ms(1))) {
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) {
const Location &loc = gps.location(1);
last_send_time_ms = gps.last_message_time_ms(1);
mavlink_msg_gps2_raw_send(
chan,
gps.last_fix_time_ms(1)*(uint64_t)1000,
gps.status(1),
loc.lat,
loc.lng,
loc.alt * 10UL,
gps.get_hdop(1),
65535,
gps.ground_speed(1)*100, // cm/s
gps.ground_course_cd(1), // 1/100 degrees,
gps.num_sats(1),
0,
0);
}
}
#endif
}
static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
mavlink_msg_servo_output_raw_send(
@ -334,7 +286,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
case MSG_GPS_RAW:
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
send_gps_raw(chan);
gcs[chan-MAVLINK_COMM_0].send_gps_raw(gps);
break;
case MSG_RADIO_OUT: