mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Copter: remove GPS_STATUS message
this message is huge and slow, and is pointless as we have num_satellites in GPS_RAW_INT
This commit is contained in:
parent
152ae7d737
commit
578b1b68ad
@ -43,7 +43,6 @@ public:
|
||||
void init(FastSerial *port) {
|
||||
_port = port;
|
||||
initialised = true;
|
||||
last_gps_satellites = 255;
|
||||
}
|
||||
|
||||
/// Update GCS state.
|
||||
@ -86,9 +85,6 @@ public:
|
||||
// set to true if this GCS link is active
|
||||
bool initialised;
|
||||
|
||||
// used to prevent wasting bandwidth with GPS_STATUS messages
|
||||
uint8_t last_gps_satellites;
|
||||
|
||||
protected:
|
||||
/// The stream we are communicating over
|
||||
FastSerial * _port;
|
||||
|
@ -482,18 +482,6 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
|
||||
accel_offsets.z);
|
||||
}
|
||||
|
||||
static void NOINLINE send_gps_status(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_gps_status_send(
|
||||
chan,
|
||||
g_gps->num_sats,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL);
|
||||
}
|
||||
|
||||
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_mission_current_send(
|
||||
@ -615,11 +603,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||
send_raw_imu3(chan);
|
||||
break;
|
||||
|
||||
case MSG_GPS_STATUS:
|
||||
CHECK_PAYLOAD_SIZE(GPS_STATUS);
|
||||
send_gps_status(chan);
|
||||
break;
|
||||
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
||||
send_current_waypoint(chan);
|
||||
@ -926,16 +909,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
send_message(MSG_GPS_RAW);
|
||||
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
||||
send_message(MSG_LIMITS_STATUS);
|
||||
|
||||
|
||||
if (last_gps_satellites != g_gps->num_sats) {
|
||||
// this message is mostly a huge waste of bandwidth,
|
||||
// except it is the only message that gives the number
|
||||
// of visible satellites. So only send it when that
|
||||
// changes.
|
||||
send_message(MSG_GPS_STATUS);
|
||||
last_gps_satellites = g_gps->num_sats;
|
||||
}
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_POSITION)) {
|
||||
|
@ -247,7 +247,6 @@ enum ap_message {
|
||||
MSG_RAW_IMU1,
|
||||
MSG_RAW_IMU2,
|
||||
MSG_RAW_IMU3,
|
||||
MSG_GPS_STATUS,
|
||||
MSG_GPS_RAW,
|
||||
MSG_SERVO_OUT,
|
||||
MSG_NEXT_WAYPOINT,
|
||||
|
Loading…
Reference in New Issue
Block a user