APM: don't send GPS_STATUS MAVLink message
it now provides no useful information as satellites_visible is in GPS_RAW_INT in MAVLink 1.0
This commit is contained in:
parent
96dc207d1d
commit
04111ebcdf
@ -43,7 +43,6 @@ public:
|
|||||||
void init(FastSerial *port) {
|
void init(FastSerial *port) {
|
||||||
_port = port;
|
_port = port;
|
||||||
initialised = true;
|
initialised = true;
|
||||||
last_gps_satellites = 255;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Update GCS state.
|
/// Update GCS state.
|
||||||
@ -86,9 +85,6 @@ public:
|
|||||||
// set to true if this GCS link is active
|
// set to true if this GCS link is active
|
||||||
bool initialised;
|
bool initialised;
|
||||||
|
|
||||||
// used to prevent wasting bandwidth with GPS_STATUS messages
|
|
||||||
uint8_t last_gps_satellites;
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// The stream we are communicating over
|
/// The stream we are communicating over
|
||||||
FastSerial * _port;
|
FastSerial * _port;
|
||||||
|
@ -447,18 +447,6 @@ static void NOINLINE send_wind(mavlink_channel_t chan)
|
|||||||
wind.z);
|
wind.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)
|
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_mission_current_send(
|
mavlink_msg_mission_current_send(
|
||||||
@ -584,11 +572,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
|||||||
break;
|
break;
|
||||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
case MSG_GPS_STATUS:
|
|
||||||
CHECK_PAYLOAD_SIZE(GPS_STATUS);
|
|
||||||
send_gps_status(chan);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_CURRENT_WAYPOINT:
|
case MSG_CURRENT_WAYPOINT:
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
||||||
send_current_waypoint(chan);
|
send_current_waypoint(chan);
|
||||||
@ -889,15 +872,6 @@ GCS_MAVLINK::data_stream_send(void)
|
|||||||
send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working
|
send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working
|
||||||
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
||||||
send_message(MSG_FENCE_STATUS);
|
send_message(MSG_FENCE_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)) {
|
if (stream_trigger(STREAM_POSITION)) {
|
||||||
|
@ -130,7 +130,6 @@ enum ap_message {
|
|||||||
MSG_RAW_IMU1,
|
MSG_RAW_IMU1,
|
||||||
MSG_RAW_IMU2,
|
MSG_RAW_IMU2,
|
||||||
MSG_RAW_IMU3,
|
MSG_RAW_IMU3,
|
||||||
MSG_GPS_STATUS,
|
|
||||||
MSG_GPS_RAW,
|
MSG_GPS_RAW,
|
||||||
MSG_SERVO_OUT,
|
MSG_SERVO_OUT,
|
||||||
MSG_NEXT_WAYPOINT,
|
MSG_NEXT_WAYPOINT,
|
||||||
|
Loading…
Reference in New Issue
Block a user