GCS_MAVLink: remove unneeded telemetry_delayed parameter
Also make it protected
This commit is contained in:
parent
187b4ef349
commit
3338de827e
@ -212,10 +212,6 @@ public:
|
||||
// return current packet overhead for a channel
|
||||
static uint8_t packet_overhead_chan(mavlink_channel_t chan);
|
||||
|
||||
// FIXME: move this to be private/protected once possible
|
||||
bool telemetry_delayed(mavlink_channel_t chan);
|
||||
virtual uint32_t telem_delay() const = 0;
|
||||
|
||||
protected:
|
||||
|
||||
// overridable method to check for packet acceptance. Allows for
|
||||
@ -269,6 +265,9 @@ protected:
|
||||
void handle_timesync(mavlink_message_t *msg);
|
||||
void handle_statustext(mavlink_message_t *msg);
|
||||
|
||||
bool telemetry_delayed() const;
|
||||
virtual uint32_t telem_delay() const = 0;
|
||||
|
||||
private:
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||
|
@ -1520,13 +1520,13 @@ float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
}
|
||||
|
||||
// are we still delaying telemetry to try to avoid Xbee bricking?
|
||||
bool GCS_MAVLINK::telemetry_delayed(mavlink_channel_t _chan)
|
||||
bool GCS_MAVLINK::telemetry_delayed() const
|
||||
{
|
||||
uint32_t tnow = AP_HAL::millis() >> 10;
|
||||
if (tnow > telem_delay()) {
|
||||
return false;
|
||||
}
|
||||
if (_chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
||||
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
||||
// this is USB telemetry, so won't be an Xbee
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user