diff --git a/src/core/mavsdk_impl.cpp b/src/core/mavsdk_impl.cpp index 7d2b8857bb..905996cf8a 100644 --- a/src/core/mavsdk_impl.cpp +++ b/src/core/mavsdk_impl.cpp @@ -641,7 +641,7 @@ void MavsdkImpl::set_base_mode(uint8_t base_mode) _base_mode = base_mode; } -bool MavsdkImpl::get_base_mode() const +uint8_t MavsdkImpl::get_base_mode() const { return _base_mode; } diff --git a/src/core/mavsdk_impl.h b/src/core/mavsdk_impl.h index e03e049dd1..2b1ed0c135 100644 --- a/src/core/mavsdk_impl.h +++ b/src/core/mavsdk_impl.h @@ -86,7 +86,7 @@ class MavsdkImpl { MAVLinkAddress own_address{}; void set_base_mode(uint8_t base_mode); - bool get_base_mode() const; + uint8_t get_base_mode() const; void set_custom_mode(uint32_t custom_mode); uint32_t get_custom_mode() const; diff --git a/src/core/system_impl.cpp b/src/core/system_impl.cpp index 1ca580d180..c59808e04a 100644 --- a/src/core/system_impl.cpp +++ b/src/core/system_impl.cpp @@ -1381,7 +1381,7 @@ void SystemImpl::set_server_armed(bool armed) bool SystemImpl::is_server_armed() const { - return _parent.get_base_mode() & (MAV_MODE_FLAG_SAFETY_ARMED == MAV_MODE_FLAG_SAFETY_ARMED); + return (_parent.get_base_mode() & MAV_MODE_FLAG_SAFETY_ARMED) == MAV_MODE_FLAG_SAFETY_ARMED; } void SystemImpl::set_custom_mode(uint32_t custom_mode) diff --git a/src/plugins/mission_raw_server/mission_raw_server_impl.cpp b/src/plugins/mission_raw_server/mission_raw_server_impl.cpp index 524e3a96d4..b0a61b38f4 100644 --- a/src/plugins/mission_raw_server/mission_raw_server_impl.cpp +++ b/src/plugins/mission_raw_server/mission_raw_server_impl.cpp @@ -310,7 +310,7 @@ void MissionRawServerImpl::set_current_item_complete() _parent->get_own_system_id(), _parent->get_own_component_id(), &mission_reached, - _current_seq); + static_cast(_current_seq)); _parent->send_message(mission_reached); if (_current_seq + 1 == _current_mission.size()) { _mission_completed = true; @@ -320,7 +320,7 @@ void MissionRawServerImpl::set_current_item_complete() } } -void MissionRawServerImpl::set_current_seq(uint16_t seq) +void MissionRawServerImpl::set_current_seq(std::size_t seq) { if (_current_mission.size() <= static_cast(seq)) { return; @@ -337,8 +337,8 @@ void MissionRawServerImpl::set_current_seq(uint16_t seq) _parent->get_own_system_id(), _parent->get_own_component_id(), &mission_current, - _current_seq); + static_cast(_current_seq)); _parent->send_message(mission_current); } -} // namespace mavsdk \ No newline at end of file +} // namespace mavsdk diff --git a/src/plugins/mission_raw_server/mission_raw_server_impl.h b/src/plugins/mission_raw_server/mission_raw_server_impl.h index 1fdb82dbaf..02f06bcde1 100644 --- a/src/plugins/mission_raw_server/mission_raw_server_impl.h +++ b/src/plugins/mission_raw_server/mission_raw_server_impl.h @@ -41,7 +41,7 @@ class MissionRawServerImpl : public PluginImplBase { std::atomic _stop_work_thread = false; std::vector _current_mission; - uint16_t _current_seq; + std::size_t _current_seq; struct MissionData { mutable std::recursive_mutex mutex{}; @@ -66,7 +66,7 @@ class MissionRawServerImpl : public PluginImplBase { MAVLinkMissionTransfer::Result result, const std::vector& int_items); - void set_current_seq(uint16_t seq); + void set_current_seq(std::size_t seq); void add_task(std::function task) { @@ -82,4 +82,4 @@ class MissionRawServerImpl : public PluginImplBase { bool _enable_absolute_gimbal_yaw_angle{true}; }; -} // namespace mavsdk \ No newline at end of file +} // namespace mavsdk