diff --git a/ArduCopter/GCS_MAVLink_Copter.cpp b/ArduCopter/GCS_MAVLink_Copter.cpp index 1c0f2115d838c..eed5307ccd6cd 100644 --- a/ArduCopter/GCS_MAVLink_Copter.cpp +++ b/ArduCopter/GCS_MAVLink_Copter.cpp @@ -317,10 +317,22 @@ uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const { return copter.g.sysid_my_gcs; } +void GCS_MAVLINK_Copter::set_sysid_my_gcs(uint8_t sysid) const +{ + copter.g.sysid_my_gcs.set_and_save(sysid); +} bool GCS_MAVLINK_Copter::sysid_enforce() const { return copter.g2.sysid_enforce; } +bool GCS_MAVLINK_Copter::control_takeover_allowed() const +{ + return copter.g2.control_takeover_allowed; +} +void GCS_MAVLINK_Copter::set_control_takeover_allowed(bool takeoverAllowed) const +{ + return copter.g2.control_takeover_allowed.set_and_save(takeoverAllowed); +} uint32_t GCS_MAVLINK_Copter::telem_delay() const { diff --git a/ArduCopter/GCS_MAVLink_Copter.h b/ArduCopter/GCS_MAVLink_Copter.h index 558804c05e8c3..4aee2ccaf13bf 100644 --- a/ArduCopter/GCS_MAVLink_Copter.h +++ b/ArduCopter/GCS_MAVLink_Copter.h @@ -22,7 +22,10 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; uint8_t sysid_my_gcs() const override; + void set_sysid_my_gcs(uint8_t sysid) const override; bool sysid_enforce() const override; + bool control_takeover_allowed() const override; + void set_control_takeover_allowed(bool takeoverAllowed) const override; bool params_ready() const override; void send_banner() override; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index ecfff2862cc27..2c3c0687c8cff 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -815,6 +815,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0), + // @Param: ALLOW_TAKEOVER + // @DisplayName: Allow takeover + // @Description: This controls if a GCS requesting control will be granted control automatically or the current GCS in control will need to be asked first + // @Values: 0:NotAllowed,1:Allowed + // @User: Advanced + AP_GROUPINFO("ALLOW_TAKEOVER", 12, ParametersG2, control_takeover_allowed, 1), + // 12 was AP_Stats // 13 was AP_Gripper diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index f07ebf297eaf0..b8fc338f48bbe 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -536,6 +536,8 @@ class ParametersG2 { // whether to enforce acceptance of packets only from sysid_my_gcs AP_Int8 sysid_enforce; + AP_Int8 control_takeover_allowed; + #if AP_COPTER_ADVANCED_FAILSAFE_ENABLED // advanced failsafe library AP_AdvancedFailsafe_Copter afs; diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 3002e773c02e5..480d2aa6b73d8 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -162,6 +162,9 @@ void Copter::failsafe_gcs_check() // failsafe_gcs_on_event - actions to take when GCS contact is lost void Copter::failsafe_gcs_on_event(void) { + // Set gcs allow_override true here, so other gcs can take control automatically, vehicle no longer has active controlling GCS + copter.g2.control_takeover_allowed.set_and_save(true); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); RC_Channels::clear_overrides(); diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 9e0b0bee2c725..af2a919018532 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -271,7 +271,10 @@ class GCS_MAVLINK uint16_t cap_message_interval(uint16_t interval_ms) const; virtual uint8_t sysid_my_gcs() const = 0; + virtual void set_sysid_my_gcs(uint8_t sysid) const = 0; virtual bool sysid_enforce() const { return false; } + virtual bool control_takeover_allowed() const = 0; + virtual void set_control_takeover_allowed(bool takeoverAllowed) const = 0; // NOTE: param_name here must point to a 16+1 byte buffer - so do // NOT try to pass in a static-char-* unless it does have that @@ -618,6 +621,8 @@ class GCS_MAVLINK bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const; MAV_RESULT handle_command_request_message(const mavlink_command_int_t &packet); + MAV_RESULT handle_request_operator_control(const mavlink_command_int_t &packet, const mavlink_message_t &msg); + MAV_RESULT handle_START_RX_PAIR(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet); @@ -806,10 +811,14 @@ class GCS_MAVLINK MAV_RESULT handle_servorelay_message(const mavlink_command_int_t &packet); bool send_relay_status() const; + void send_control_status() const; + static bool command_long_stores_location(const MAV_CMD command); bool calibrate_gyros(); + bool is_control_request_packet(const mavlink_message_t &msg) const; + /// The stream we are communicating over AP_HAL::UARTDriver *_port; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 41edb3152ae36..bbdac515718ff 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1151,6 +1151,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #endif { MAVLINK_MSG_ID_AVAILABLE_MODES, MSG_AVAILABLE_MODES}, { MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR, MSG_AVAILABLE_MODES_MONITOR}, + { MAVLINK_MSG_ID_CONTROL_STATUS, MSG_CONTROL_STATUS}, }; for (uint8_t i=0; i