GCS_Mavlink: Move high_latency_link_enabled to GCS
This commit is contained in:
parent
fab1c47b27
commit
a39a933cbd
@ -116,12 +116,14 @@ void GCS::send_named_float(const char *name, float value) const
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
void GCS::enable_high_latency_connections(bool enabled)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs(); i++) {
|
||||
GCS_MAVLINK &c = *chan(i);
|
||||
c.high_latency_link_enabled = enabled && c.is_high_latency_link;
|
||||
}
|
||||
high_latency_link_enabled = enabled;
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "High Latency %s", enabled ? "enabled" : "disabled");
|
||||
}
|
||||
|
||||
bool GCS::get_high_latency_status()
|
||||
{
|
||||
return high_latency_link_enabled;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
/*
|
||||
|
@ -418,8 +418,8 @@ public:
|
||||
bool is_private(void) const { return is_private(chan); }
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
// return true if the link should be sending. Will return false if is a high latency link AND is not active
|
||||
bool should_send() { return is_high_latency_link ? high_latency_link_enabled : true; }
|
||||
// true if this is a high latency link
|
||||
bool is_high_latency_link;
|
||||
#endif
|
||||
|
||||
/*
|
||||
@ -683,9 +683,6 @@ protected:
|
||||
|
||||
MAV_RESULT handle_control_high_latency(const mavlink_command_long_t &packet);
|
||||
|
||||
// true if this is a high latency link
|
||||
bool is_high_latency_link;
|
||||
bool high_latency_link_enabled;
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||
@ -1212,7 +1209,9 @@ public:
|
||||
uint8_t get_channel_from_port_number(uint8_t port_num);
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
bool high_latency_link_enabled;
|
||||
void enable_high_latency_connections(bool enabled);
|
||||
bool get_high_latency_status();
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
virtual uint8_t sysid_this_mav() const = 0;
|
||||
|
@ -97,7 +97,7 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
// if it's a disabled high latency channel, don't send
|
||||
GCS_MAVLINK *link = gcs().chan(chan);
|
||||
if (!link->should_send()) {
|
||||
if (link->is_high_latency_link && !gcs().get_high_latency_status()) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user