uORB::Publication improvements and cleanup (#14784)

- 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.
This commit is contained in:
Daniel Agar 2020-05-04 11:09:30 -04:00 committed by GitHub
parent 8e2c52a31a
commit 466b5db36f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
68 changed files with 218 additions and 381 deletions

View File

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

View File

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

View File

@ -117,7 +117,7 @@ private:
SF1XX::SF1XX(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
I2C(DRV_DIST_DEVTYPE_SF1XX, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_rangefinder(DRV_DIST_DEVTYPE_SF1XX, rotation)
_px4_rangefinder(DRV_DIST_DEVTYPE_SF1XX, ORB_PRIO_DEFAULT, rotation)
{
}

View File

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

View File

@ -47,7 +47,7 @@ const uint8_t BMI055_accel::_checked_registers[BMI055_ACCEL_NUM_CHECKED_REGISTER
BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path_accel, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055(DRV_ACC_DEVTYPE_BMI055, "bmi055_accel", path_accel, bus_option, bus, 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")),

View File

@ -52,7 +52,7 @@ const uint8_t BMI055_gyro::_checked_registers[BMI055_GYRO_NUM_CHECKED_REGISTERS]
BMI055_gyro::BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_gyro, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055(DRV_GYR_DEVTYPE_BMI055, "bmi055_gyro", path_gyro, bus_option, bus, 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"))

View File

@ -56,7 +56,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")),

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -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},
@ -72,7 +72,11 @@ PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Ro
_device_id{device_id},
_rotation{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()
@ -80,6 +84,11 @@ 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)

View File

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

View File

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

View File

@ -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(); }

View File

@ -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},
@ -73,7 +73,11 @@ PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation r
_device_id{device_id},
_rotation{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();
}
@ -83,6 +87,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)

View File

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

View File

@ -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;
_sensor_mag_pub.get().temperature = NAN;
@ -53,6 +55,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)

View File

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

View File

@ -35,13 +35,20 @@
#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) :
_distance_sensor_pub{ORB_ID(distance_sensor), priority}
{
_distance_sensor_pub.advertise();
set_device_id(device_id);
set_orientation(device_orientation);
}
PX4Rangefinder::~PX4Rangefinder()
{
_distance_sensor_pub.unadvertise();
}
void PX4Rangefinder::set_device_type(uint8_t device_type)
{
// TODO: range finders should have device ids

View File

@ -44,9 +44,9 @@ class PX4Rangefinder
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() = default;
~PX4Rangefinder();
void print_status();

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -34,7 +34,7 @@
#pragma once
#include <stdint.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/ulog_stream.h>
#include <uORB/topics/ulog_stream_ack.h>

View File

@ -45,7 +45,7 @@
#include <stdlib.h>
#include <time.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/uORBTopics.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_command_ack.h>

View File

@ -51,7 +51,7 @@
#include <lib/ecl/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/version/version.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include "mavlink_receiver.h"
#include "mavlink_main.h"

View File

@ -71,7 +71,7 @@
#include <px4_platform_common/posix.h>
#include <systemlib/mavlink_log.h>
#include <systemlib/uthash/utlist.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/mavlink_log.h>
#include <uORB/topics/mission_result.h>
#include <uORB/topics/radio_status.h>

View File

@ -46,7 +46,6 @@
#include "mavlink_bridge_header.h"
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rc_parameter_map.h>
#include <uORB/topics/uavcan_parameter_request.h>

View File

@ -54,7 +54,6 @@
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <px4_platform_common/module_params.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/actuator_controls.h>

View File

@ -33,7 +33,7 @@
#pragma once
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <drivers/drv_hrt.h>
#include <lib/tunes/tunes.h>

View File

@ -54,7 +54,6 @@
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/home_position.h>

View File

@ -44,7 +44,6 @@
#include <stdio.h>
#include <px4_platform_common/defines.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
px4::AppState MuorbTestExample::appState;

View File

@ -58,7 +58,7 @@
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/geofence_result.h>
#include <uORB/topics/home_position.h>

View File

@ -154,7 +154,7 @@ void VotedSensorsUpdate::parametersUpdate()
_gyro.enabled[driver_index] = (device_enabled == 1);
if (!_gyro.enabled[driver_index]) {
_gyro.priority[driver_index] = 0;
_gyro.priority[driver_index] = ORB_PRIO_UNINITIALIZED;
}
gyro_calibration_s gscale{};
@ -250,7 +250,7 @@ void VotedSensorsUpdate::parametersUpdate()
_accel.enabled[driver_index] = (device_enabled == 1);
if (!_accel.enabled[driver_index]) {
_accel.priority[driver_index] = 0;
_accel.priority[driver_index] = ORB_PRIO_UNINITIALIZED;
}
accel_calibration_s ascale{};
@ -387,7 +387,7 @@ void VotedSensorsUpdate::parametersUpdate()
// the mags that were published after the initial parameterUpdate
// would be given the priority even if disabled. Reset it to 0 in this case
if (!_mag.enabled[topic_instance]) {
_mag.priority[topic_instance] = 0;
_mag.priority[topic_instance] = ORB_PRIO_UNINITIALIZED;
}
mag_calibration_s mscale{};
@ -702,14 +702,16 @@ bool VotedSensorsUpdate::checkFailover(SensorData &sensor, const char *sensor_na
((flags & DataValidator::ERROR_FLAG_HIGH_ERRDENSITY) ? " ERR DNST" : ""));
// reduce priority of failed sensor to the minimum
sensor.priority[failover_index] = 1;
sensor.priority[failover_index] = ORB_PRIO_MIN;
PX4_ERR("Sensor %s #%i failed. Reconfiguring sensor priorities.", sensor_name, failover_index);
int ctr_valid = 0;
for (uint8_t i = 0; i < sensor.subscription_count; i++) {
if (sensor.priority[i] > 1) { ctr_valid++; }
if (sensor.priority[i] > ORB_PRIO_MIN) {
ctr_valid++;
}
PX4_WARN("Remaining sensors after failover event %u: %s #%u priority: %u", failover_index, sensor_name, i,
sensor.priority[i]);

View File

@ -54,7 +54,6 @@
#include <lib/mag_compensation/MagCompensation.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/sensor_accel_integrated.h>
#include <uORB/topics/sensor_combined.h>
@ -156,7 +155,7 @@ private:
uORB::Subscription subscription[SENSOR_COUNT_MAX]; /**< raw sensor data subscription */
DataValidatorGroup voter{1};
unsigned int last_failover_count{0};
uint8_t priority[SENSOR_COUNT_MAX] {}; /**< sensor priority */
ORB_PRIO priority[SENSOR_COUNT_MAX] {}; /**< sensor priority */
uint8_t last_best_vote{0}; /**< index of the latest best vote */
uint8_t subscription_count{0};
bool enabled[SENSOR_COUNT_MAX] {true, true, true, true};

View File

@ -35,7 +35,7 @@
#include "temperature_calibration/temperature_calibration.h"
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_command.h>
#include <systemlib/mavlink_log.h>

View File

@ -39,7 +39,7 @@
* @author Beat Küng <beat-kueng@gmx.net>
*/
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/sensor_gyro.h>
#include <mathlib/mathlib.h>
#include <px4_platform_common/atomic.h>

View File

@ -43,8 +43,6 @@ if(NOT "${PX4_BOARD}" MATCHES "px4_io") # TODO: fix this hack (move uORB to plat
ORBSet.hpp
Publication.hpp
PublicationMulti.hpp
PublicationQueued.hpp
PublicationQueuedMulti.hpp
Subscription.cpp
Subscription.hpp
SubscriptionCallback.hpp

View File

@ -40,16 +40,47 @@
#include <px4_platform_common/defines.h>
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include "uORBDeviceNode.hpp"
#include <uORB/topics/uORBTopics.hpp>
namespace uORB
{
class PublicationBase
{
public:
bool advertised() const { return _handle != nullptr; }
bool unadvertise() { return (DeviceNode::unadvertise(_handle) == PX4_OK); }
orb_id_t get_topic() const { return get_orb_meta(_orb_id); }
protected:
PublicationBase(ORB_ID id) : _orb_id(id) {}
~PublicationBase()
{
if (_handle != nullptr) {
// don't automatically unadvertise queued publications (eg vehicle_command)
if (static_cast<DeviceNode *>(_handle)->get_queue_size() == 1) {
unadvertise();
}
}
}
orb_advert_t _handle{nullptr};
const ORB_ID _orb_id;
};
/**
* Base publication wrapper class
* uORB publication wrapper class
*/
template<typename T>
class Publication
template<typename T, uint8_t ORB_QSIZE = 1>
class Publication : public PublicationBase
{
public:
@ -58,8 +89,17 @@ public:
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
Publication(const orb_metadata *meta) : _meta(meta) {}
~Publication() { orb_unadvertise(_handle); }
Publication(ORB_ID id) : PublicationBase(id) {}
Publication(const orb_metadata *meta) : PublicationBase(static_cast<ORB_ID>(meta->o_id)) {}
bool advertise()
{
if (!advertised()) {
_handle = orb_advertise_queue(get_topic(), nullptr, ORB_QSIZE);
}
return advertised();
}
/**
* Publish the struct
@ -67,25 +107,12 @@ public:
*/
bool publish(const T &data)
{
if (_handle != nullptr) {
return (orb_publish(_meta, _handle, &data) == PX4_OK);
} else {
orb_advert_t handle = orb_advertise(_meta, &data);
if (handle != nullptr) {
_handle = handle;
return true;
}
if (!advertised()) {
advertise();
}
return false;
return (DeviceNode::publish(get_topic(), _handle, &data) == PX4_OK);
}
protected:
const orb_metadata *_meta;
orb_advert_t _handle{nullptr};
};
/**
@ -100,8 +127,8 @@ public:
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
PublicationData(ORB_ID id) : Publication<T>(id) {}
PublicationData(const orb_metadata *meta) : Publication<T>(meta) {}
~PublicationData() = default;
T &get() { return _data; }
void set(const T &data) { _data = data; }
@ -118,4 +145,10 @@ private:
T _data{};
};
template<class T>
using PublicationQueued = Publication<T, T::ORB_QUEUE_LENGTH>;
} // namespace uORB

View File

@ -42,14 +42,16 @@
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include "Publication.hpp"
namespace uORB
{
/**
* Base publication multi wrapper class
*/
template<typename T>
class PublicationMulti
template<typename T, uint8_t QSIZE = 1>
class PublicationMulti : public PublicationBase
{
public:
@ -59,12 +61,25 @@ public:
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
* @param priority The priority for multi pub/sub, 0 means don't publish as multi
*/
PublicationMulti(const orb_metadata *meta, uint8_t priority = ORB_PRIO_DEFAULT) :
_meta(meta),
PublicationMulti(ORB_ID id, ORB_PRIO priority = ORB_PRIO_DEFAULT) :
PublicationBase(id),
_priority(priority)
{}
~PublicationMulti() { orb_unadvertise(_handle); }
PublicationMulti(const orb_metadata *meta, ORB_PRIO priority = ORB_PRIO_DEFAULT) :
PublicationBase(static_cast<ORB_ID>(meta->o_id)),
_priority(priority)
{}
bool advertise()
{
if (!advertised()) {
int instance = 0;
_handle = orb_advertise_multi_queue(get_topic(), nullptr, &instance, _priority, QSIZE);
}
return advertised();
}
/**
* Publish the struct
@ -72,28 +87,15 @@ public:
*/
bool publish(const T &data)
{
if (_handle != nullptr) {
return (orb_publish(_meta, _handle, &data) == PX4_OK);
} else {
int instance = 0;
orb_advert_t handle = orb_advertise_multi(_meta, &data, &instance, _priority);
if (handle != nullptr) {
_handle = handle;
return true;
}
if (!advertised()) {
advertise();
}
return false;
return (orb_publish(get_topic(), _handle, &data) == PX4_OK);
}
protected:
const orb_metadata *_meta;
orb_advert_t _handle{nullptr};
const uint8_t _priority;
const ORB_PRIO _priority;
};
/**
@ -109,12 +111,13 @@ public:
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
* @param priority The priority for multi pub
*/
PublicationMultiData(const orb_metadata *meta, uint8_t priority = ORB_PRIO_DEFAULT) :
PublicationMultiData(ORB_ID id, ORB_PRIO priority = ORB_PRIO_DEFAULT) :
PublicationMulti<T>(id, priority)
{}
PublicationMultiData(const orb_metadata *meta, ORB_PRIO priority = ORB_PRIO_DEFAULT) :
PublicationMulti<T>(meta, priority)
{}
~PublicationMultiData() = default;
T &get() { return _data; }
void set(const T &data) { _data = data; }
@ -130,4 +133,8 @@ private:
T _data{};
};
template<class T>
using PublicationQueuedMulti = PublicationMulti<T, T::ORB_QUEUE_LENGTH>;
} // namespace uORB

View File

@ -1,94 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file PublicationQueued.hpp
*
*/
#pragma once
#include <px4_platform_common/defines.h>
#include <systemlib/err.h>
#include <uORB/uORB.h>
namespace uORB
{
/**
* Queued publication with queue length set as a message constant (ORB_QUEUE_LENGTH)
*/
template<typename T>
class PublicationQueued
{
public:
/**
* Constructor
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
PublicationQueued(const orb_metadata *meta) : _meta(meta) {}
~PublicationQueued()
{
//orb_unadvertise(_handle);
}
/**
* Publish the struct
* @param data The uORB message struct we are updating.
*/
bool publish(const T &data)
{
if (_handle != nullptr) {
return (orb_publish(_meta, _handle, &data) == PX4_OK);
} else {
orb_advert_t handle = orb_advertise_queue(_meta, &data, T::ORB_QUEUE_LENGTH);
if (handle != nullptr) {
_handle = handle;
return true;
}
}
return false;
}
protected:
const orb_metadata *_meta;
orb_advert_t _handle{nullptr};
};
} // namespace uORB

View File

@ -1,101 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file PublicationQueuedMulti.hpp
*
*/
#pragma once
#include <px4_platform_common/defines.h>
#include <systemlib/err.h>
#include <uORB/uORB.h>
namespace uORB
{
/**
* Queued publication with queue length set as a message constant (ORB_QUEUE_LENGTH)
*/
template<typename T>
class PublicationQueuedMulti
{
public:
/**
* Constructor
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
PublicationQueuedMulti(const orb_metadata *meta, uint8_t priority = ORB_PRIO_DEFAULT) :
_meta(meta),
_priority(priority)
{}
~PublicationQueuedMulti()
{
//orb_unadvertise(_handle);
}
/**
* Publish the struct
* @param data The uORB message struct we are updating.
*/
bool publish(const T &data)
{
if (_handle != nullptr) {
return (orb_publish(_meta, _handle, &data) == PX4_OK);
} else {
int instance = 0;
orb_advert_t handle = orb_advertise_multi_queue(_meta, &data, &instance, _priority, T::ORB_QUEUE_LENGTH);
if (handle != nullptr) {
_handle = handle;
return true;
}
}
return false;
}
protected:
const orb_metadata *_meta;
orb_advert_t _handle{nullptr};
const uint8_t _priority;
};
} // namespace uORB

View File

@ -50,14 +50,13 @@ orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *da
return uORB::Manager::get_instance()->orb_advertise(meta, data, queue_size);
}
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
int priority)
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, ORB_PRIO priority)
{
return uORB::Manager::get_instance()->orb_advertise_multi(meta, data, instance, priority);
}
orb_advert_t orb_advertise_multi_queue(const struct orb_metadata *meta, const void *data, int *instance,
int priority, unsigned int queue_size)
ORB_PRIO priority, unsigned int queue_size)
{
return uORB::Manager::get_instance()->orb_advertise_multi(meta, data, instance, priority, queue_size);
}
@ -113,7 +112,7 @@ int orb_group_count(const struct orb_metadata *meta)
return instance;
}
int orb_priority(int handle, int32_t *priority)
int orb_priority(int handle, enum ORB_PRIO *priority)
{
return uORB::Manager::get_instance()->orb_priority(handle, priority);
}

View File

@ -152,13 +152,13 @@ extern orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const v
* @see uORB::Manager::orb_advertise_multi()
*/
extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
int priority) __EXPORT;
enum ORB_PRIO priority) __EXPORT;
/**
* @see uORB::Manager::orb_advertise_multi()
*/
extern orb_advert_t orb_advertise_multi_queue(const struct orb_metadata *meta, const void *data, int *instance,
int priority, unsigned int queue_size) __EXPORT;
enum ORB_PRIO priority, unsigned int queue_size) __EXPORT;
/**
* @see uORB::Manager::orb_unadvertise()
@ -179,8 +179,7 @@ extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, con
* @see uORB::Manager::orb_advertise_multi() for meaning of the individual parameters
*/
static inline int orb_publish_auto(const struct orb_metadata *meta, orb_advert_t *handle, const void *data,
int *instance,
int priority)
int *instance, enum ORB_PRIO priority)
{
if (!*handle) {
*handle = orb_advertise_multi(meta, data, instance, priority);
@ -237,7 +236,7 @@ extern int orb_group_count(const struct orb_metadata *meta) __EXPORT;
/**
* @see uORB::Manager::orb_priority()
*/
extern int orb_priority(int handle, int32_t *priority) __EXPORT;
extern int orb_priority(int handle, enum ORB_PRIO *priority) __EXPORT;
/**
* @see uORB::Manager::orb_set_interval()

View File

@ -47,7 +47,7 @@ static constexpr unsigned orb_maxpath = 64;
struct orb_advertdata {
const struct orb_metadata *meta;
int *instance;
int priority;
ORB_PRIO priority;
};
}

View File

@ -58,8 +58,7 @@ uORB::DeviceMaster::~DeviceMaster()
px4_sem_destroy(&_lock);
}
int
uORB::DeviceMaster::advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, int priority)
int uORB::DeviceMaster::advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, ORB_PRIO priority)
{
int ret = PX4_ERROR;

View File

@ -65,7 +65,7 @@ class uORB::DeviceMaster
{
public:
int advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, int priority);
int advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, ORB_PRIO priority);
/**
* Public interface for getDeviceNodeLocked(). Takes care of synchronization.

View File

@ -55,11 +55,11 @@ uORB::DeviceNode::SubscriberData *uORB::DeviceNode::filp_to_sd(cdev::file_t *fil
}
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path,
uint8_t priority, uint8_t queue_size) :
ORB_PRIO priority, uint8_t queue_size) :
CDev(path),
_meta(meta),
_instance(instance),
_priority(priority),
_instance(instance),
_queue_size(queue_size)
{
}
@ -432,7 +432,7 @@ int uORB::DeviceNode::unadvertise(orb_advert_t handle)
}
#ifdef ORB_COMMUNICATOR
int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, int priority)
int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, ORB_PRIO priority)
{
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
@ -445,7 +445,7 @@ int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta, int priorit
/*
//TODO: Check if we need this since we only unadvertise when things all shutdown and it doesn't actually remove the device
int16_t uORB::DeviceNode::topic_unadvertised(const orb_metadata *meta, int priority)
int16_t uORB::DeviceNode::topic_unadvertised(const orb_metadata *meta, ORB_PRIO priority)
{
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
if (ch != nullptr && meta != nullptr) {

View File

@ -55,7 +55,7 @@ class SubscriptionCallback;
class uORB::DeviceNode : public cdev::CDev, public ListNode<uORB::DeviceNode *>
{
public:
DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path, uint8_t priority,
DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path, ORB_PRIO priority,
uint8_t queue_size = 1);
virtual ~DeviceNode();
@ -116,8 +116,8 @@ public:
static int unadvertise(orb_advert_t handle);
#ifdef ORB_COMMUNICATOR
static int16_t topic_advertised(const orb_metadata *meta, int priority);
//static int16_t topic_unadvertised(const orb_metadata *meta, int priority);
static int16_t topic_advertised(const orb_metadata *meta, ORB_PRIO priority);
//static int16_t topic_unadvertised(const orb_metadata *meta, ORB_PRIO priority);
/**
* processes a request for add subscription from remote
@ -263,8 +263,8 @@ private:
uint32_t _lost_messages = 0; /**< nr of lost messages for all subscribers. If two subscribers lose the same
message, it is counted as two. */
ORB_PRIO _priority; /**< priority of the topic */
const uint8_t _instance; /**< orb multi instance identifier */
uint8_t _priority; /**< priority of the topic */
bool _advertised{false}; /**< has ever been advertised (not necessarily published data yet) */
uint8_t _queue_size; /**< maximum number of elements in the queue */
int8_t _subscriber_count{0};

View File

@ -168,7 +168,7 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
}
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
int priority, unsigned int queue_size)
ORB_PRIO priority, unsigned int queue_size)
{
#ifdef ORB_USE_PUBLISHER_RULES
@ -227,12 +227,14 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
uORB::DeviceNode::topic_advertised(meta, priority);
#endif /* ORB_COMMUNICATOR */
/* the advertiser must perform an initial publish to initialise the object */
result = orb_publish(meta, advertiser, data);
/* the advertiser may perform an initial publish to initialise the object */
if (data != nullptr) {
result = orb_publish(meta, advertiser, data);
if (result == PX4_ERROR) {
PX4_WARN("orb_publish failed");
return nullptr;
if (result == PX4_ERROR) {
PX4_ERR("orb_publish failed %s", meta->o_name);
return nullptr;
}
}
return advertiser;
@ -305,7 +307,7 @@ int uORB::Manager::orb_check(int handle, bool *updated)
return px4_ioctl(handle, ORBIOCUPDATED, (unsigned long)(uintptr_t)updated);
}
int uORB::Manager::orb_priority(int handle, int32_t *priority)
int uORB::Manager::orb_priority(int handle, enum ORB_PRIO *priority)
{
return px4_ioctl(handle, ORBIOCGPRIORITY, (unsigned long)(uintptr_t)priority);
}
@ -322,23 +324,7 @@ int uORB::Manager::orb_get_interval(int handle, unsigned *interval)
return ret;
}
int uORB::Manager::node_advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance, int priority)
{
int ret = PX4_ERROR;
if (get_device_master()) {
ret = _device_master->advertise(meta, is_advertiser, instance, priority);
}
/* it's PX4_OK if it already exists */
if ((PX4_OK != ret) && (EEXIST == errno)) {
ret = PX4_OK;
}
return ret;
}
int uORB::Manager::node_open(const struct orb_metadata *meta, bool advertiser, int *instance, int priority)
int uORB::Manager::node_open(const struct orb_metadata *meta, bool advertiser, int *instance, ORB_PRIO priority)
{
char path[orb_maxpath];
int fd = -1;
@ -376,36 +362,32 @@ int uORB::Manager::node_open(const struct orb_metadata *meta, bool advertiser, i
/* we may need to advertise the node... */
if (fd < 0) {
/* try to create the node */
ret = node_advertise(meta, advertiser, instance, priority);
ret = PX4_ERROR;
if (get_device_master()) {
ret = _device_master->advertise(meta, advertiser, instance, priority);
}
/* it's OK if it already exists */
if ((ret != PX4_OK) && (EEXIST == errno)) {
ret = PX4_OK;
}
if (ret == PX4_OK) {
/* update the path, as it might have been updated during the node_advertise call */
/* update the path, as it might have been updated during the node advertise call */
ret = uORB::Utils::node_mkpath(path, meta, instance);
if (ret != PX4_OK) {
/* on success, try to open again */
if (ret == PX4_OK) {
fd = px4_open(path, (advertiser) ? PX4_F_WRONLY : PX4_F_RDONLY);
} else {
errno = -ret;
return PX4_ERROR;
}
}
/* on success, try to open again */
if (ret == PX4_OK) {
fd = px4_open(path, (advertiser) ? PX4_F_WRONLY : PX4_F_RDONLY);
}
}
/*
else if (advertiser) {
* We have a valid fd and are an advertiser.
* This can happen if the topic is already subscribed/published, and orb_advertise() is called,
* where instance==nullptr.
* We would need to set the priority here (via px4_ioctl(fd, ...) and a new IOCTL), but orb_advertise()
* uses ORB_PRIO_DEFAULT, and a subscriber also creates the node with ORB_PRIO_DEFAULT. So we don't need
* to do anything here.
}
*/
if (fd < 0) {
errno = EIO;
return PX4_ERROR;

View File

@ -161,8 +161,8 @@ public:
* ORB_DEFINE with no corresponding ORB_DECLARE)
* this function will return -1 and set errno to ENOENT.
*/
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
int priority, unsigned int queue_size = 1);
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, ORB_PRIO priority,
unsigned int queue_size = 1);
/**
* Unadvertise a topic.
@ -318,7 +318,7 @@ public:
* independent of the startup order of the associated publishers.
* @return OK on success, PX4_ERROR otherwise with errno set accordingly.
*/
int orb_priority(int handle, int32_t *priority);
int orb_priority(int handle, enum ORB_PRIO *priority);
/**
* Set the minimum interval between which updates are seen for a subscription.
@ -376,12 +376,6 @@ public:
#endif /* ORB_COMMUNICATOR */
private: // class methods
/**
* Advertise a node; don't consider it an error if the node has
* already been advertised.
*/
int node_advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance = nullptr,
int priority = ORB_PRIO_DEFAULT);
/**
* Common implementation for orb_advertise and orb_subscribe.
@ -390,7 +384,7 @@ private: // class methods
* advertisers.
*/
int node_open(const struct orb_metadata *meta, bool advertiser, int *instance = nullptr,
int priority = ORB_PRIO_DEFAULT);
ORB_PRIO priority = ORB_PRIO_DEFAULT);
private: // data members
static Manager *_Instance;

View File

@ -386,7 +386,7 @@ int uORBTest::UnitTest::test_multi()
}
/* test priorities */
int prio;
ORB_PRIO prio;
if (PX4_OK != orb_priority(sfd0, &prio)) {
return test_fail("prio #0");

View File

@ -39,7 +39,7 @@
*/
#include "input_mavlink.h"
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_roi.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/position_setpoint_triplet.h>

View File

@ -41,7 +41,7 @@
#include "output.h"
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_command.h>
namespace vmount

View File

@ -48,7 +48,7 @@
*/
#include "vtol_att_control_main.h"
#include <systemlib/mavlink_log.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
using namespace matrix;

View File

@ -45,7 +45,7 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/led_control.h>
static void usage();

View File

@ -43,7 +43,7 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/log.h>
#include <px4_platform_common/module.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/test_motor.h>
extern "C" __EXPORT int motor_test_main(int argc, char *argv[]);