From fceb4eaa3f66cba3d76896b05251530b7cc04cab Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Thu, 3 Dec 2020 15:56:44 +0200 Subject: [PATCH] uORB: Change cpuload topic int vehicle_cpuload This avoids clashes with NuttX cpuload_s datatype. Signed-off-by: Jukka Laitinen --- msg/CMakeLists.txt | 2 +- msg/{cpuload.msg => vehicle_cpuload.msg} | 0 .../Arming/PreFlightCheck/checks/cpuResourceCheck.cpp | 4 ++-- src/modules/commander/Commander.hpp | 6 +++--- src/modules/events/status_display.h | 4 ++-- src/modules/load_mon/LoadMon.cpp | 2 +- src/modules/load_mon/LoadMon.hpp | 4 ++-- src/modules/logger/logged_topics.cpp | 2 +- src/modules/mavlink/streams/SYS_STATUS.hpp | 6 +++--- 9 files changed, 15 insertions(+), 15 deletions(-) rename msg/{cpuload.msg => vehicle_cpuload.msg} (100%) diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 6904bfce54..8b9798be3f 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -53,7 +53,7 @@ set(msg_files collision_report.msg commander_state.msg control_allocator_status.msg - cpuload.msg + vehicle_cpuload.msg differential_pressure.msg distance_sensor.msg ekf2_timestamps.msg diff --git a/msg/cpuload.msg b/msg/vehicle_cpuload.msg similarity index 100% rename from msg/cpuload.msg rename to msg/vehicle_cpuload.msg diff --git a/src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp b/src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp index bf84206a7c..007cd0e1ea 100644 --- a/src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp +++ b/src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include using namespace time_literals; @@ -45,7 +45,7 @@ bool PreFlightCheck::cpuResourceCheck(orb_advert_t *mavlink_log_pub, const bool { bool success = true; - uORB::SubscriptionData cpuload_sub{ORB_ID(cpuload)}; + uORB::SubscriptionData cpuload_sub{ORB_ID(vehicle_cpuload)}; cpuload_sub.update(); float cpuload_percent_max; diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 0c14b2f755..a162bf6dc0 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -63,7 +63,7 @@ #include #include #include -#include +#include #include #include #include @@ -377,7 +377,7 @@ private: bool _should_set_home_on_takeoff{true}; bool _system_power_usb_connected{false}; - cpuload_s _cpuload{}; + vehicle_cpuload_s _cpuload{}; geofence_result_s _geofence_result{}; vehicle_land_detected_s _land_detector{}; safety_s _safety{}; @@ -395,7 +395,7 @@ private: // Subscriptions uORB::Subscription _actuator_controls_sub{ORB_ID_VEHICLE_ATTITUDE_CONTROLS}; uORB::Subscription _cmd_sub {ORB_ID(vehicle_command)}; - uORB::Subscription _cpuload_sub{ORB_ID(cpuload)}; + uORB::Subscription _cpuload_sub{ORB_ID(vehicle_cpuload)}; uORB::Subscription _esc_status_sub{ORB_ID(esc_status)}; uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _geofence_result_sub{ORB_ID(geofence_result)}; diff --git a/src/modules/events/status_display.h b/src/modules/events/status_display.h index 259b422900..2237b0620c 100644 --- a/src/modules/events/status_display.h +++ b/src/modules/events/status_display.h @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include #include #include @@ -80,7 +80,7 @@ protected: void publish(); uORB::SubscriptionData _battery_status_sub{ORB_ID(battery_status)}; - uORB::SubscriptionData _cpu_load_sub{ORB_ID(cpuload)}; + uORB::SubscriptionData _cpu_load_sub{ORB_ID(vehicle_cpuload)}; uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::SubscriptionData _vehicle_status_flags_sub{ORB_ID(vehicle_status_flags)}; diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index 6ae74d46f9..7771d8bed2 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -162,7 +162,7 @@ void LoadMon::cpuload() const float interval_idletime = 1.0f; #endif - cpuload_s cpuload{}; + vehicle_cpuload_s cpuload{}; #if defined(__PX4_LINUX) /* following calculation is based on free(1) * https://gitlab.com/procps-ng/procps/-/blob/master/proc/sysinfo.c */ diff --git a/src/modules/load_mon/LoadMon.hpp b/src/modules/load_mon/LoadMon.hpp index afdbb23d2b..ce0b09796b 100644 --- a/src/modules/load_mon/LoadMon.hpp +++ b/src/modules/load_mon/LoadMon.hpp @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include #if defined(__PX4_LINUX) @@ -90,7 +90,7 @@ private: uORB::Publication _task_stack_info_pub{ORB_ID(task_stack_info)}; #endif - uORB::Publication _cpuload_pub {ORB_ID(cpuload)}; + uORB::Publication _cpuload_pub {ORB_ID(vehicle_cpuload)}; #if defined(__PX4_LINUX) FILE *_proc_fd = nullptr; diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index e0ce45bff3..0c6cfc0043 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -59,7 +59,7 @@ void LoggedTopics::add_default_topics() add_topic("camera_trigger_secondary"); add_topic("cellular_status", 200); add_topic("commander_state"); - add_topic("cpuload"); + add_topic("vehicle_cpuload"); add_topic("esc_status", 250); add_topic("follow_target", 500); add_topic("generator_status"); diff --git a/src/modules/mavlink/streams/SYS_STATUS.hpp b/src/modules/mavlink/streams/SYS_STATUS.hpp index 4fe5d8e046..8e583f2661 100644 --- a/src/modules/mavlink/streams/SYS_STATUS.hpp +++ b/src/modules/mavlink/streams/SYS_STATUS.hpp @@ -35,7 +35,7 @@ #define SYS_STATUS_HPP #include -#include +#include #include class MavlinkStreamSysStatus : public MavlinkStream @@ -58,7 +58,7 @@ private: explicit MavlinkStreamSysStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {} uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; - uORB::Subscription _cpuload_sub{ORB_ID(cpuload)}; + uORB::Subscription _cpuload_sub{ORB_ID(vehicle_cpuload)}; uORB::SubscriptionMultiArray _battery_status_subs{ORB_ID::battery_status}; bool send() override @@ -67,7 +67,7 @@ private: vehicle_status_s status{}; _status_sub.copy(&status); - cpuload_s cpuload{}; + vehicle_cpuload_s cpuload{}; _cpuload_sub.copy(&cpuload); battery_status_s battery_status[battery_status_s::MAX_INSTANCES] {};