Browse Source

ArduCopter: move handling of last-seen-SYSID_MYGCS up to GCS base class

zr-v5.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
09a9bd73a4
  1. 1
      ArduCopter/Copter.h
  2. 20
      ArduCopter/GCS_Mavlink.cpp
  3. 1
      ArduCopter/GCS_Mavlink.h
  4. 9
      ArduCopter/events.cpp
  5. 2
      ArduCopter/failsafe.cpp

1
ArduCopter/Copter.h

@ -386,7 +386,6 @@ private: @@ -386,7 +386,6 @@ private:
// Failsafe
struct {
uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed

20
ArduCopter/GCS_Mavlink.cpp

@ -562,13 +562,6 @@ void GCS_MAVLINK_Copter::send_banner() @@ -562,13 +562,6 @@ void GCS_MAVLINK_Copter::send_banner()
copter.motors->get_type_string());
}
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
void GCS_MAVLINK_Copter::handle_rc_channels_override(const mavlink_message_t &msg)
{
copter.failsafe.last_heartbeat_ms = AP_HAL::millis();
GCS_MAVLINK::handle_rc_channels_override(msg);
}
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
{
copter.command_ack_counter++;
@ -999,14 +992,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) @@ -999,14 +992,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: // MAV ID: 0
{
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
if (msg.sysid != copter.g.sysid_my_gcs) break;
copter.failsafe.last_heartbeat_ms = AP_HAL::millis();
break;
}
case MAVLINK_MSG_ID_MANUAL_CONTROL:
{
if (msg.sysid != copter.g.sysid_my_gcs) {
@ -1031,8 +1016,9 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) @@ -1031,8 +1016,9 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
manual_override(copter.channel_throttle, packet.z, 0, 1000, tnow);
manual_override(copter.channel_yaw, packet.r, 1000, 2000, tnow);
// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
copter.failsafe.last_heartbeat_ms = tnow;
// a manual control message is considered to be a 'heartbeat'
// from the ground station for failsafe purposes
gcs().sysid_myggcs_seen(tnow);
break;
}

1
ArduCopter/GCS_Mavlink.h

@ -49,7 +49,6 @@ private: @@ -49,7 +49,6 @@ private:
void handle_command_ack(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
void handle_rc_channels_override(const mavlink_message_t &msg) override;
bool try_send_message(enum ap_message id) override;
void packetReceived(const mavlink_status_t &status,

9
ArduCopter/events.cpp

@ -112,13 +112,18 @@ void Copter::handle_battery_failsafe(const char *type_str, const int8_t action) @@ -112,13 +112,18 @@ void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
void Copter::failsafe_gcs_check()
{
// Bypass GCS failsafe checks if disabled or GCS never connected
if (g.failsafe_gcs == FS_GCS_DISABLED || failsafe.last_heartbeat_ms == 0) {
if (g.failsafe_gcs == FS_GCS_DISABLED) {
return;
}
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
if (gcs_last_seen_ms == 0) {
return;
}
// calc time since last gcs update
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
const uint32_t last_gcs_update_ms = millis() - failsafe.last_heartbeat_ms;
const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
// Determine which event to trigger

2
ArduCopter/failsafe.cpp

@ -84,6 +84,6 @@ void Copter::afs_fs_check(void) @@ -84,6 +84,6 @@ void Copter::afs_fs_check(void)
#else
const bool fence_breached = false;
#endif
g2.afs.check(failsafe.last_heartbeat_ms, fence_breached, last_radio_update_ms);
g2.afs.check(fence_breached, last_radio_update_ms);
}
#endif

Loading…
Cancel
Save