Copter: move telemetry_delayed up into base class

This commit is contained in:
Peter Barker 2016-05-30 09:54:36 +10:00 committed by Andrew Tridgell
parent 1e146256cc
commit e977d85e0c
3 changed files with 5 additions and 16 deletions

View File

@ -649,7 +649,6 @@ private:
void send_rpm(mavlink_channel_t chan);
void rpm_update();
void send_pid_tuning(mavlink_channel_t chan);
bool telemetry_delayed(mavlink_channel_t chan);
void gcs_send_message(enum ap_message id);
void gcs_send_mission_item_reached_message(uint16_t mission_index);
void gcs_data_stream_send(void);

View File

@ -499,27 +499,15 @@ void Copter::send_pid_tuning(mavlink_channel_t chan)
}
}
// are we still delaying telemetry to try to avoid Xbee bricking?
bool Copter::telemetry_delayed(mavlink_channel_t chan)
uint32_t GCS_MAVLINK_Copter::telem_delay() const
{
uint32_t tnow = millis() >> 10;
if (tnow > (uint32_t)g.telem_delay) {
return false;
return (uint32_t)(copter.g.telem_delay);
}
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
// this is USB telemetry, so won't be an Xbee
return false;
}
// we're either on the 2nd UART, or no USB cable is connected
// we need to delay telemetry by the TELEM_DELAY time
return true;
}
// try to send a message, return false if it won't fit in the serial tx buffer
bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
{
if (copter.telemetry_delayed(chan)) {
if (telemetry_delayed(chan)) {
return false;
}

View File

@ -11,6 +11,8 @@ public:
protected:
uint32_t telem_delay() const override;
private:
void handleMessage(mavlink_message_t * msg) override;