uORB: Change cpuload topic int vehicle_cpuload

This avoids clashes with NuttX cpuload_s datatype.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This commit is contained in:
Jukka Laitinen 2020-12-03 15:56:44 +02:00
parent fc6b2d8122
commit fceb4eaa3f
9 changed files with 15 additions and 15 deletions

View File

@ -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

View File

@ -37,7 +37,7 @@
#include <systemlib/mavlink_log.h>
#include <lib/parameters/param.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/vehicle_cpuload.h>
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_s> cpuload_sub{ORB_ID(cpuload)};
uORB::SubscriptionData<vehicle_cpuload_s> cpuload_sub{ORB_ID(vehicle_cpuload)};
cpuload_sub.update();
float cpuload_percent_max;

View File

@ -63,7 +63,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/vehicle_cpuload.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/estimator_selector_status.h>
@ -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)};

View File

@ -45,7 +45,7 @@
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/vehicle_cpuload.h>
#include <uORB/topics/led_control.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_status_flags.h>
@ -80,7 +80,7 @@ protected:
void publish();
uORB::SubscriptionData<battery_status_s> _battery_status_sub{ORB_ID(battery_status)};
uORB::SubscriptionData<cpuload_s> _cpu_load_sub{ORB_ID(cpuload)};
uORB::SubscriptionData<vehicle_cpuload_s> _cpu_load_sub{ORB_ID(vehicle_cpuload)};
uORB::SubscriptionData<vehicle_status_s> _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::SubscriptionData<vehicle_status_flags_s> _vehicle_status_flags_sub{ORB_ID(vehicle_status_flags)};

View File

@ -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 */

View File

@ -45,7 +45,7 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform/cpuload.h>
#include <uORB/Publication.hpp>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/vehicle_cpuload.h>
#include <uORB/topics/task_stack_info.h>
#if defined(__PX4_LINUX)
@ -90,7 +90,7 @@ private:
uORB::Publication<task_stack_info_s> _task_stack_info_pub{ORB_ID(task_stack_info)};
#endif
uORB::Publication<cpuload_s> _cpuload_pub {ORB_ID(cpuload)};
uORB::Publication<vehicle_cpuload_s> _cpuload_pub {ORB_ID(vehicle_cpuload)};
#if defined(__PX4_LINUX)
FILE *_proc_fd = nullptr;

View File

@ -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");

View File

@ -35,7 +35,7 @@
#define SYS_STATUS_HPP
#include <uORB/topics/battery_status.h>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/vehicle_cpuload.h>
#include <uORB/topics/vehicle_status.h>
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_s, battery_status_s::MAX_INSTANCES> _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] {};