Skip to content

Commit

Permalink
uORB::Publication improvements and cleanup (#14784)
Browse files Browse the repository at this point in the history
 - create common uORB::PublicationBase
 - uORB::PublicationQueued types are now type aliases
 - ORB_PRIO use enum type everywhere to avoid accidental misuse
 - PX4Accelerometer/PX4Gyroscope/etc driver libs explicitly advertise on construction, unadvertise on destruction. This is a workaround for any potential issues that might appear when accel/gyro cdev and uORB indexing doesn't align.
  • Loading branch information
dagar authored and bkueng committed May 13, 2020
1 parent 74620cc commit 1c74c62
Show file tree
Hide file tree
Showing 67 changed files with 219 additions and 386 deletions.
1 change: 0 additions & 1 deletion src/drivers/camera_capture/camera_capture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@
#include <px4_platform_common/workqueue.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/camera_trigger.h>
#include <uORB/topics/vehicle_command.h>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/camera_trigger/camera_trigger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@
#include <parameters/param.h>
#include <systemlib/mavlink_log.h>

#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/camera_trigger.h>
#include <uORB/topics/camera_capture.h>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/gps/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
#include <px4_platform_common/cli.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/gps_dump.h>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi055/BMI055_accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_accel", path_accel, bus_option, bus, DRV_ACC_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_accel_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_accel_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi055_accel_bad_registers")),
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi055/BMI055_gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ BMI055_gyro::BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_g
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_gyro", path_gyro, bus_option, bus, DRV_GYR_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_gyro_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_registers"))
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi088/BMI088_accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ BMI088_accel::BMI088_accel(I2CSPIBusOption bus_option, int bus, const char *path
enum Rotation rotation,
int bus_frequency, spi_mode_e spi_mode) :
BMI088("bmi088_accel", path_accel, bus_option, bus, DRV_ACC_DEVTYPE_BMI088, device, spi_mode, bus_frequency, rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi088_accel_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi088_accel_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi088_accel_bad_registers")),
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi088/BMI088_gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ BMI088_gyro::BMI088_gyro(I2CSPIBusOption bus_option, int bus, const char *path_g
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI088("bmi088_gyro", path_gyro, bus_option, bus, DRV_GYR_DEVTYPE_BMI088, device, spi_mode, bus_frequency,
rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi088_gyro_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi088_gyro_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi088_gyro_bad_registers")),
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/px4io/px4io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@

#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
Expand Down
1 change: 0 additions & 1 deletion src/drivers/safety_button/SafetyButton.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/safety.h>
Expand Down
1 change: 0 additions & 1 deletion src/drivers/telemetry/iridiumsbd/IridiumSBD.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include <drivers/drv_hrt.h>

#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/topics/iridiumsbd_status.h>
#include <uORB/topics/subsystem_info.h>

Expand Down
1 change: 0 additions & 1 deletion src/drivers/uavcan/uavcan_servers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@
#include <drivers/device/Device.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/topics/uavcan_parameter_value.h>
#include <uORB/topics/vehicle_command_ack.h>

Expand Down
1 change: 0 additions & 1 deletion src/lib/avoidance/ObstacleAvoidance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@
#include <drivers/drv_hrt.h>

#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/position_controller_status.h>
#include <uORB/topics/vehicle_command.h>
Expand Down
1 change: 0 additions & 1 deletion src/lib/collision_prevention/CollisionPrevention.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@
#include <px4_platform_common/module_params.h>
#include <systemlib/mavlink_log.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/collision_constraints.h>
#include <uORB/topics/distance_sensor.h>
Expand Down
11 changes: 10 additions & 1 deletion src/lib/drivers/accelerometer/PX4Accelerometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ static constexpr unsigned clipping(const int16_t samples[16], int16_t clip_limit
return clip_count;
}

PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
PX4Accelerometer::PX4Accelerometer(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
CDev(nullptr),
_sensor_pub{ORB_ID(sensor_accel), priority},
_sensor_fifo_pub{ORB_ID(sensor_accel_fifo), priority},
Expand All @@ -73,14 +73,23 @@ PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Ro
_rotation{rotation},
_rotation_dcm{get_rot_matrix(rotation)}
{
// register class and advertise immediately to keep instance numbering in sync
_class_device_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH);
_sensor_pub.advertise();
_sensor_integrated_pub.advertise();
_sensor_status_pub.advertise();
}

PX4Accelerometer::~PX4Accelerometer()
{
if (_class_device_instance != -1) {
unregister_class_devname(ACCEL_BASE_DEVICE_PATH, _class_device_instance);
}

_sensor_pub.unadvertise();
_sensor_fifo_pub.unadvertise();
_sensor_integrated_pub.unadvertise();
_sensor_status_pub.unadvertise();
}

int PX4Accelerometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
Expand Down
4 changes: 2 additions & 2 deletions src/lib/drivers/accelerometer/PX4Accelerometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <lib/drivers/device/integrator.h>
#include <lib/ecl/geo/geo.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/PublicationQueuedMulti.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_accel_fifo.h>
#include <uORB/topics/sensor_accel_integrated.h>
Expand All @@ -49,7 +49,7 @@
class PX4Accelerometer : public cdev::CDev
{
public:
PX4Accelerometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
PX4Accelerometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
~PX4Accelerometer() override;

int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override;
Expand Down
5 changes: 4 additions & 1 deletion src/lib/drivers/barometer/PX4Barometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,12 @@

#include <lib/drivers/device/Device.hpp>

PX4Barometer::PX4Barometer(uint32_t device_id, uint8_t priority) :
PX4Barometer::PX4Barometer(uint32_t device_id, ORB_PRIO priority) :
CDev(nullptr),
_sensor_baro_pub{ORB_ID(sensor_baro), priority}
{
_class_device_instance = register_class_devname(BARO_BASE_DEVICE_PATH);
_sensor_baro_pub.advertise();

_sensor_baro_pub.get().device_id = device_id;
}
Expand All @@ -50,6 +51,8 @@ PX4Barometer::~PX4Barometer()
if (_class_device_instance != -1) {
unregister_class_devname(BARO_BASE_DEVICE_PATH, _class_device_instance);
}

_sensor_baro_pub.unadvertise();
}

void
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/barometer/PX4Barometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class PX4Barometer : public cdev::CDev
{

public:
PX4Barometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT);
PX4Barometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT);
~PX4Barometer() override;

const sensor_baro_s &get() { return _sensor_baro_pub.get(); }
Expand Down
11 changes: 10 additions & 1 deletion src/lib/drivers/gyroscope/PX4Gyroscope.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ static constexpr unsigned clipping(const int16_t samples[16], int16_t clip_limit
return clip_count;
}

PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
PX4Gyroscope::PX4Gyroscope(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
CDev(nullptr),
ModuleParams(nullptr),
_sensor_pub{ORB_ID(sensor_gyro), priority},
Expand All @@ -74,7 +74,11 @@ PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation r
_rotation{rotation},
_rotation_dcm{get_rot_matrix(rotation)}
{
// register class and advertise immediately to keep instance numbering in sync
_class_device_instance = register_class_devname(GYRO_BASE_DEVICE_PATH);
_sensor_pub.advertise();
_sensor_integrated_pub.advertise();
_sensor_status_pub.advertise();

updateParams();
}
Expand All @@ -84,6 +88,11 @@ PX4Gyroscope::~PX4Gyroscope()
if (_class_device_instance != -1) {
unregister_class_devname(GYRO_BASE_DEVICE_PATH, _class_device_instance);
}

_sensor_pub.unadvertise();
_sensor_fifo_pub.unadvertise();
_sensor_integrated_pub.unadvertise();
_sensor_status_pub.unadvertise();
}

int PX4Gyroscope::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
Expand Down
4 changes: 2 additions & 2 deletions src/lib/drivers/gyroscope/PX4Gyroscope.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <lib/drivers/device/integrator.h>
#include <px4_platform_common/module_params.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/PublicationQueuedMulti.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_gyro.h>
#include <uORB/topics/sensor_gyro_fifo.h>
#include <uORB/topics/sensor_gyro_integrated.h>
Expand All @@ -49,7 +49,7 @@
class PX4Gyroscope : public cdev::CDev, public ModuleParams
{
public:
PX4Gyroscope(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
PX4Gyroscope(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
~PX4Gyroscope() override;

int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override;
Expand Down
6 changes: 5 additions & 1 deletion src/lib/drivers/magnetometer/PX4Magnetometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,15 @@

#include <lib/drivers/device/Device.hpp>

PX4Magnetometer::PX4Magnetometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
PX4Magnetometer::PX4Magnetometer(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
CDev(nullptr),
_sensor_mag_pub{ORB_ID(sensor_mag), priority},
_rotation{rotation}
{
_class_device_instance = register_class_devname(MAG_BASE_DEVICE_PATH);

_sensor_mag_pub.advertise();

_sensor_mag_pub.get().device_id = device_id;
_sensor_mag_pub.get().scaling = 1.0f;
}
Expand All @@ -52,6 +54,8 @@ PX4Magnetometer::~PX4Magnetometer()
if (_class_device_instance != -1) {
unregister_class_devname(MAG_BASE_DEVICE_PATH, _class_device_instance);
}

_sensor_mag_pub.unadvertise();
}

int PX4Magnetometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/magnetometer/PX4Magnetometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class PX4Magnetometer : public cdev::CDev
{

public:
PX4Magnetometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
PX4Magnetometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
~PX4Magnetometer() override;

int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override;
Expand Down
5 changes: 4 additions & 1 deletion src/lib/drivers/rangefinder/PX4Rangefinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,18 +35,21 @@

#include <lib/drivers/device/Device.hpp>

PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t priority, const uint8_t device_orientation) :
PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const ORB_PRIO priority, const uint8_t device_orientation) :
CDev(nullptr),
_distance_sensor_pub{ORB_ID(distance_sensor), priority}
{
_class_device_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH);
_distance_sensor_pub.advertise();

set_device_id(device_id);
set_orientation(device_orientation);
}

PX4Rangefinder::~PX4Rangefinder()
{
_distance_sensor_pub.unadvertise();

if (_class_device_instance != -1) {
unregister_class_devname(RANGE_FINDER_BASE_DEVICE_PATH, _class_device_instance);
}
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/rangefinder/PX4Rangefinder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class PX4Rangefinder : public cdev::CDev

public:
PX4Rangefinder(const uint32_t device_id,
const uint8_t priority = ORB_PRIO_DEFAULT,
const ORB_PRIO priority = ORB_PRIO_DEFAULT,
const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING);
~PX4Rangefinder() override;

Expand Down
2 changes: 1 addition & 1 deletion src/lib/flight_tasks/FlightTasks.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include "FlightTask.hpp"
#include "FlightTasks_generated.hpp"
#include <lib/weather_vane/WeatherVane.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_command.h>
Expand Down
2 changes: 1 addition & 1 deletion src/lib/mixer_module/mixer_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

#include <lib/mixer/MultirotorMixer/MultirotorMixer.hpp>

#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <px4_platform_common/log.h>

using namespace time_literals;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <px4_platform_common/px4_config.h>
#include <lib/parameters/param.h>
#include <systemlib/mavlink_log.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>

Expand Down
1 change: 0 additions & 1 deletion src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@

// publications
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/test_motor.h>
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/accelerometer_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -556,7 +556,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub

if (device_id[cur_accel] != 0) {
// Get priority
int32_t prio;
ORB_PRIO prio = ORB_PRIO_UNINITIALIZED;
orb_priority(worker_data.subs[cur_accel], &prio);

if (prio > device_prio_max) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/gyro_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,7 +332,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)

if (worker_data.device_id[cur_gyro] != 0) {
// Get priority
int32_t prio;
ORB_PRIO prio = ORB_PRIO_UNINITIALIZED;
orb_priority(worker_data.gyro_sensor_sub[cur_gyro], &prio);

if (prio > device_prio_max) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/mag_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -639,7 +639,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma

if (device_ids[cur_mag] != 0) {
// Get priority
int32_t prio;
ORB_PRIO prio = ORB_PRIO_UNINITIALIZED;
orb_priority(worker_data.sub_mag[cur_mag], &prio);

if (prio > device_prio_max) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/events/send_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>

Expand Down
2 changes: 1 addition & 1 deletion src/modules/events/status_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@

#include <drivers/drv_hrt.h>

#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/cpuload.h>
Expand Down
1 change: 0 additions & 1 deletion src/modules/load_mon/load_mon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/cpuload.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/topics/cpuload.h>
#include <uORB/topics/task_stack_info.h>

Expand Down
Loading

0 comments on commit 1c74c62

Please sign in to comment.