Browse Source

Copter: removed GPS_STATUS message

this message is huge, and completely pointless now that we have
num_satellites in GPS_RAW_INT
master
Andrew Tridgell 12 years ago
parent
commit
b079a96eaf
  1. 4
      ArduCopter/GCS.h
  2. 15
      ArduCopter/GCS_Mavlink.pde
  3. 1
      ArduCopter/defines.h

4
ArduCopter/GCS.h

@ -40,7 +40,6 @@ public: @@ -40,7 +40,6 @@ public:
void init(AP_HAL::UARTDriver *port) {
_port = port;
initialised = true;
last_gps_satellites = 255;
}
/// Update GCS state.
@ -75,9 +74,6 @@ public: @@ -75,9 +74,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
AP_HAL::UARTDriver * _port;

15
ArduCopter/GCS_Mavlink.pde

@ -614,11 +614,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, @@ -614,11 +614,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);
@ -994,16 +989,6 @@ GCS_MAVLINK::data_stream_send(void) @@ -994,16 +989,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)) {

1
ArduCopter/defines.h

@ -249,7 +249,6 @@ enum ap_message { @@ -249,7 +249,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…
Cancel
Save