diff --git a/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.cpp b/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.cpp index 81f4f4ef9e..d8a123cd28 100644 --- a/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.cpp +++ b/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.cpp @@ -18,6 +18,15 @@ GimbalProtocolV2::GimbalProtocolV2( _gimbal_manager_compid(gimbal_manager_compid) {} +GimbalProtocolV2::~GimbalProtocolV2() +{ + if (_is_mavlink_manager_status_registered) { + _is_mavlink_manager_status_registered = false; + + _system_impl.unregister_mavlink_message_handler(MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, this); + } +} + void GimbalProtocolV2::process_gimbal_manager_status(const mavlink_message_t& message) { Gimbal::ControlMode new_control_mode; diff --git a/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.h b/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.h index 3c2b1d4b36..e7f60a3104 100644 --- a/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.h +++ b/src/mavsdk/plugins/gimbal/gimbal_protocol_v2.h @@ -12,7 +12,7 @@ class GimbalProtocolV2 : public GimbalProtocolBase { const mavlink_gimbal_manager_information_t& information, uint8_t gimbal_manager_sysid, uint8_t gimbal_manager_compid); - ~GimbalProtocolV2() override = default; + ~GimbalProtocolV2() override; Gimbal::Result set_pitch_and_yaw(float pitch_deg, float yaw_deg) override; void set_pitch_and_yaw_async(