mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Copter: move telemetry_delayed up into base class
This commit is contained in:
parent
1e146256cc
commit
e977d85e0c
@ -649,7 +649,6 @@ private:
|
|||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
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_message(enum ap_message id);
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
|
@ -499,27 +499,15 @@ void Copter::send_pid_tuning(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// are we still delaying telemetry to try to avoid Xbee bricking?
|
uint32_t GCS_MAVLINK_Copter::telem_delay() const
|
||||||
bool Copter::telemetry_delayed(mavlink_channel_t chan)
|
|
||||||
{
|
{
|
||||||
uint32_t tnow = millis() >> 10;
|
return (uint32_t)(copter.g.telem_delay);
|
||||||
if (tnow > (uint32_t)g.telem_delay) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
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
|
// 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)
|
bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
||||||
{
|
{
|
||||||
if (copter.telemetry_delayed(chan)) {
|
if (telemetry_delayed(chan)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -11,6 +11,8 @@ public:
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
uint32_t telem_delay() const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void handleMessage(mavlink_message_t * msg) override;
|
void handleMessage(mavlink_message_t * msg) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user