From 003f03df9f8a831b4645bd09c238ca8dd5ebf68b Mon Sep 17 00:00:00 2001 From: Vladimir Ermakov Date: Sun, 3 Mar 2024 10:21:54 +0100 Subject: [PATCH] fix cpplint errors --- mavros/src/plugins/global_position.cpp | 2 +- mavros/src/plugins/home_position.cpp | 3 +-- mavros/src/plugins/imu.cpp | 3 +-- mavros/src/plugins/local_position.cpp | 3 +-- mavros/src/plugins/sys_status.cpp | 8 +++++--- 5 files changed, 9 insertions(+), 10 deletions(-) diff --git a/mavros/src/plugins/global_position.cpp b/mavros/src/plugins/global_position.cpp index f13791c69..171e93110 100644 --- a/mavros/src/plugins/global_position.cpp +++ b/mavros/src/plugins/global_position.cpp @@ -17,9 +17,9 @@ */ #include -#include #include +#include #include // NOLINT #include "rcpputils/asserts.hpp" diff --git a/mavros/src/plugins/home_position.cpp b/mavros/src/plugins/home_position.cpp index 8928615c6..57325fe60 100644 --- a/mavros/src/plugins/home_position.cpp +++ b/mavros/src/plugins/home_position.cpp @@ -16,9 +16,8 @@ * @{ */ -#include - #include +#include #include "rcpputils/asserts.hpp" #include "mavros/mavros_uas.hpp" diff --git a/mavros/src/plugins/imu.cpp b/mavros/src/plugins/imu.cpp index 49e73df8b..f8e46f363 100644 --- a/mavros/src/plugins/imu.cpp +++ b/mavros/src/plugins/imu.cpp @@ -14,10 +14,9 @@ * @{ */ -#include - #include #include +#include #include "rcpputils/asserts.hpp" #include "mavros/mavros_uas.hpp" diff --git a/mavros/src/plugins/local_position.cpp b/mavros/src/plugins/local_position.cpp index 78f5024cc..afbf868c8 100644 --- a/mavros/src/plugins/local_position.cpp +++ b/mavros/src/plugins/local_position.cpp @@ -16,9 +16,8 @@ * @{ */ -#include - #include +#include #include "rcpputils/asserts.hpp" #include "mavros/mavros_uas.hpp" diff --git a/mavros/src/plugins/sys_status.cpp b/mavros/src/plugins/sys_status.cpp index 0e1ad805d..75b7a8a4a 100644 --- a/mavros/src/plugins/sys_status.cpp +++ b/mavros/src/plugins/sys_status.cpp @@ -773,7 +773,7 @@ class SystemStatusPlugin : public plugin::Plugin // ): // for v in l1: // cog.outl(f"case enum_value(MAV_SEVERITY::{v}):") - // cog.outl(f" RCLCPP_{l2}_STREAM(node->get_logger(), \"FCU: EVENT \" << px4_id << \" with args \" << arg_str);") + // cog.outl(f" RCLCPP_{l2}_STREAM(node->get_logger(), \"FCU: EVENT \" << px4_id << \" with args \" << arg_str);") # NOLINT // cog.outl(f" break;") // ]]] case enum_value(MAV_SEVERITY::EMERGENCY): @@ -1037,8 +1037,10 @@ class SystemStatusPlugin : public plugin::Plugin mavlink::common::msg::EVENT & eventm, plugin::filter::SystemAndOk filter [[maybe_unused]]) { - uint8_t severity = eventm.log_levels & 0x0F; // take only 4 LSB, see https://mavlink.io/en/messages/common.html#EVENT - uint32_t px4_id = eventm.id & 0x00FFFFFF; // take only 24 LSB, see PX4 "constexpr uint32_t ID(const char (&name)[N])" function + // take only 4 LSB, see https://mavlink.io/en/messages/common.html#EVENT + uint8_t severity = eventm.log_levels & 0x0F; + // take only 24 LSB, see PX4 "constexpr uint32_t ID(const char (&name)[N])" function + uint32_t px4_id = eventm.id & 0x00FFFFFF; process_event_normal(severity, px4_id, eventm.arguments); auto evt_msg = mavros_msgs::msg::StatusEvent();