From eac9a6b68bc7645c00ccf91f73f9bbe7d5afad7e Mon Sep 17 00:00:00 2001 From: FengShun Date: Mon, 26 Oct 2020 12:40:50 +0800 Subject: [PATCH] Replace PublicationQueued with Publication to automatically configure ORB_QUEUE_LENGTH --- src/drivers/camera_capture/camera_capture.hpp | 2 +- src/drivers/camera_trigger/camera_trigger.cpp | 4 ++-- src/drivers/gps/gps.cpp | 2 +- src/drivers/mkblctrl/mkblctrl.cpp | 2 +- src/drivers/px4io/px4io.cpp | 4 ++-- src/drivers/rc_input/RCInput.cpp | 2 +- src/drivers/safety_button/SafetyButton.hpp | 4 ++-- src/drivers/tone_alarm/ToneAlarm.cpp | 2 +- src/drivers/uavcan/uavcan_servers.hpp | 2 +- src/lib/avoidance/ObstacleAvoidance.hpp | 2 +- src/lib/collision_prevention/CollisionPrevention.hpp | 2 +- src/lib/drivers/accelerometer/PX4Accelerometer.hpp | 2 +- src/lib/drivers/gyroscope/PX4Gyroscope.hpp | 2 +- src/lib/drivers/magnetometer/PX4Magnetometer.hpp | 2 +- src/lib/flight_tasks/FlightTasks.hpp | 2 +- src/lib/mixer_module/mixer_module.cpp | 2 +- .../Arming/ArmAuthorization/ArmAuthorization.cpp | 2 +- src/modules/commander/Commander.cpp | 10 +++++----- src/modules/commander/Commander.hpp | 4 ++-- src/modules/commander/calibration_routines.cpp | 2 +- src/modules/events/rc_loss_alarm.h | 2 +- src/modules/events/send_event.cpp | 2 +- src/modules/events/status_display.h | 2 +- src/modules/load_mon/LoadMon.hpp | 2 +- src/modules/logger/log_writer_mavlink.h | 2 +- src/modules/logger/logger.cpp | 2 +- src/modules/mavlink/mavlink_main.cpp | 2 +- src/modules/mavlink/mavlink_parameters.h | 2 +- src/modules/mavlink/mavlink_receiver.h | 8 ++++---- src/modules/mavlink/tune_publisher.h | 2 +- .../mc_pos_control/MulticopterPositionControl.hpp | 2 +- src/modules/muorb/test/muorb_test_example.cpp | 4 ++-- src/modules/navigator/navigator.h | 4 ++-- src/modules/navigator/navigator_main.cpp | 2 +- src/modules/simulator/simulator.h | 2 +- .../TemperatureCompensationModule.cpp | 4 ++-- .../temperature_calibration/task.cpp | 2 +- src/modules/uORB/Publication.hpp | 6 ------ src/modules/uORB/PublicationMulti.hpp | 4 ---- src/modules/vmount/input_mavlink.cpp | 2 +- src/modules/vmount/output_mavlink.h | 2 +- src/modules/vtol_att_control/vtol_att_control_main.cpp | 2 +- src/systemcmds/failure/failure.cpp | 2 +- src/systemcmds/led_control/led_control.cpp | 2 +- src/systemcmds/motor_test/motor_test.cpp | 2 +- src/systemcmds/tune_control/tune_control.cpp | 2 +- 46 files changed, 58 insertions(+), 68 deletions(-) diff --git a/src/drivers/camera_capture/camera_capture.hpp b/src/drivers/camera_capture/camera_capture.hpp index 26b0ea5fa4..5296aa666e 100644 --- a/src/drivers/camera_capture/camera_capture.hpp +++ b/src/drivers/camera_capture/camera_capture.hpp @@ -101,7 +101,7 @@ public: private: // Publishers - uORB::PublicationQueued _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; uORB::Publication _trigger_pub{ORB_ID(camera_trigger)}; // Subscribers diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 3c308e49bf..1eb5a13c57 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -179,7 +179,7 @@ private: orb_advert_t _trigger_pub; - uORB::PublicationQueued _cmd_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _cmd_ack_pub{ORB_ID(vehicle_command_ack)}; param_t _p_mode; param_t _p_activation_time; @@ -504,7 +504,7 @@ CameraTrigger::test() vcmd.param5 = 1.0; vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL; - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; vcmd_pub.publish(vcmd); } diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index fc3368d8eb..c49add233c 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -176,7 +176,7 @@ private: const Instance _instance; uORB::Subscription _orb_inject_data_sub{ORB_ID(gps_inject_data)}; - uORB::PublicationQueued _dump_communication_pub{ORB_ID(gps_dump)}; + uORB::Publication _dump_communication_pub{ORB_ID(gps_dump)}; gps_dump_s *_dump_to_device{nullptr}; gps_dump_s *_dump_from_device{nullptr}; bool _should_dump_communication{false}; ///< if true, dump communication diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index bb2ec9933b..52e5b65cfc 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -162,7 +162,7 @@ private: char _device[20]; orb_advert_t _t_outputs; orb_advert_t _t_esc_status; - uORB::PublicationQueued _tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication _tune_control_pub{ORB_ID(tune_control)}; unsigned int _num_outputs; bool _primary_pwm_device; bool _motortest; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 6a668a45b8..6baed918a5 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -713,7 +713,7 @@ PX4IO::init() vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_FLIGHTTERMINATION; /* send command once */ - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; vcmd_pub.publish(vcmd); /* spin here until IO's state has propagated into the system */ @@ -746,7 +746,7 @@ PX4IO::init() vcmd.command = vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM; /* send command once */ - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; vcmd_pub.publish(vcmd); /* spin here until IO's state has propagated into the system */ diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 4ede8afc53..11a6ad6d1b 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -648,7 +648,7 @@ int RCInput::custom_command(int argc, char *argv[]) const char *verb = argv[0]; if (!strcmp(verb, "bind")) { - uORB::PublicationQueued vehicle_command_pub{ORB_ID(vehicle_command)}; + uORB::Publication vehicle_command_pub{ORB_ID(vehicle_command)}; vehicle_command_s vcmd{}; vcmd.command = vehicle_command_s::VEHICLE_CMD_START_RX_PAIR; vcmd.timestamp = hrt_absolute_time(); diff --git a/src/drivers/safety_button/SafetyButton.hpp b/src/drivers/safety_button/SafetyButton.hpp index 405c9617d5..046c7ee9c6 100644 --- a/src/drivers/safety_button/SafetyButton.hpp +++ b/src/drivers/safety_button/SafetyButton.hpp @@ -79,8 +79,8 @@ private: uORB::Subscription _armed_sub{ORB_ID(actuator_armed)}; uORB::Publication _to_safety{ORB_ID(safety)}; - uORB::PublicationQueued _to_command{ORB_ID(vehicle_command)}; - uORB::PublicationQueued _to_led_control{ORB_ID(led_control)}; + uORB::Publication _to_command{ORB_ID(vehicle_command)}; + uORB::Publication _to_led_control{ORB_ID(led_control)}; uORB::Publication _to_tune_control{ORB_ID(tune_control)}; safety_s _safety{}; diff --git a/src/drivers/tone_alarm/ToneAlarm.cpp b/src/drivers/tone_alarm/ToneAlarm.cpp index 8deac60f64..5dc7ef81c3 100644 --- a/src/drivers/tone_alarm/ToneAlarm.cpp +++ b/src/drivers/tone_alarm/ToneAlarm.cpp @@ -166,7 +166,7 @@ void ToneAlarm::Run() } else if (_play_tone && !tune_control.tune_override) { // otherwise re-publish tune to process next PX4_DEBUG("tune already playing, requeing tune: %d", tune_control.tune_id); - uORB::PublicationQueued tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication tune_control_pub{ORB_ID(tune_control)}; tune_control.timestamp = hrt_absolute_time(); tune_control_pub.publish(tune_control); } diff --git a/src/drivers/uavcan/uavcan_servers.hpp b/src/drivers/uavcan/uavcan_servers.hpp index d06e1cc61f..9fed3ec28b 100644 --- a/src/drivers/uavcan/uavcan_servers.hpp +++ b/src/drivers/uavcan/uavcan_servers.hpp @@ -163,7 +163,7 @@ private: // uORB topic handle for MAVLink parameter responses uORB::Publication _param_response_pub{ORB_ID(uavcan_parameter_value)}; - uORB::PublicationQueued _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; typedef uavcan::MethodBinder &)> GetSetCallback; diff --git a/src/lib/avoidance/ObstacleAvoidance.hpp b/src/lib/avoidance/ObstacleAvoidance.hpp index 76d76c45f0..64ebc0c049 100644 --- a/src/lib/avoidance/ObstacleAvoidance.hpp +++ b/src/lib/avoidance/ObstacleAvoidance.hpp @@ -124,7 +124,7 @@ protected: uORB::Publication _pub_traj_wp_avoidance_desired{ORB_ID(vehicle_trajectory_waypoint_desired)}; /**< trajectory waypoint desired publication */ uORB::Publication _pub_pos_control_status{ORB_ID(position_controller_status)}; /**< position controller status publication */ - uORB::PublicationQueued _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command do publication */ + uORB::Publication _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command do publication */ matrix::Vector3f _curr_wp = {}; /**< current position triplet */ matrix::Vector3f _position = {}; /**< current vehicle position */ diff --git a/src/lib/collision_prevention/CollisionPrevention.hpp b/src/lib/collision_prevention/CollisionPrevention.hpp index 7af7a41a53..24a1ebbf0e 100644 --- a/src/lib/collision_prevention/CollisionPrevention.hpp +++ b/src/lib/collision_prevention/CollisionPrevention.hpp @@ -129,7 +129,7 @@ private: uORB::Publication _constraints_pub{ORB_ID(collision_constraints)}; /**< constraints publication */ uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance_fused)}; /**< obstacle_distance publication */ - uORB::PublicationQueued _vehicle_command_pub{ORB_ID(vehicle_command)}; /**< vehicle command do publication */ + uORB::Publication _vehicle_command_pub{ORB_ID(vehicle_command)}; /**< vehicle command do publication */ uORB::SubscriptionData _sub_obstacle_distance{ORB_ID(obstacle_distance)}; /**< obstacle distances received form a range sensor */ uORB::SubscriptionData _sub_vehicle_attitude{ORB_ID(vehicle_attitude)}; diff --git a/src/lib/drivers/accelerometer/PX4Accelerometer.hpp b/src/lib/drivers/accelerometer/PX4Accelerometer.hpp index c81fd5b6ca..150e2af61c 100644 --- a/src/lib/drivers/accelerometer/PX4Accelerometer.hpp +++ b/src/lib/drivers/accelerometer/PX4Accelerometer.hpp @@ -66,7 +66,7 @@ private: void Publish(const hrt_abstime ×tamp_sample, float x, float y, float z, uint8_t clip_count[3]); void UpdateClipLimit(); - uORB::PublicationQueuedMulti _sensor_pub; + uORB::PublicationMulti _sensor_pub; uORB::PublicationMulti _sensor_fifo_pub; uint32_t _device_id{0}; diff --git a/src/lib/drivers/gyroscope/PX4Gyroscope.hpp b/src/lib/drivers/gyroscope/PX4Gyroscope.hpp index dc83791498..c7746e24d1 100644 --- a/src/lib/drivers/gyroscope/PX4Gyroscope.hpp +++ b/src/lib/drivers/gyroscope/PX4Gyroscope.hpp @@ -64,7 +64,7 @@ public: private: void Publish(const hrt_abstime ×tamp_sample, float x, float y, float z); - uORB::PublicationQueuedMulti _sensor_pub; + uORB::PublicationMulti _sensor_pub; uORB::PublicationMulti _sensor_fifo_pub; uint32_t _device_id{0}; diff --git a/src/lib/drivers/magnetometer/PX4Magnetometer.hpp b/src/lib/drivers/magnetometer/PX4Magnetometer.hpp index 92d04d2946..8d367ed1ea 100644 --- a/src/lib/drivers/magnetometer/PX4Magnetometer.hpp +++ b/src/lib/drivers/magnetometer/PX4Magnetometer.hpp @@ -61,7 +61,7 @@ public: int get_class_instance() { return _class_device_instance; }; private: - uORB::PublicationQueuedMulti _sensor_pub; + uORB::PublicationMulti _sensor_pub; uint32_t _device_id{0}; const enum Rotation _rotation; diff --git a/src/lib/flight_tasks/FlightTasks.hpp b/src/lib/flight_tasks/FlightTasks.hpp index 919e7be610..490c7b13fb 100644 --- a/src/lib/flight_tasks/FlightTasks.hpp +++ b/src/lib/flight_tasks/FlightTasks.hpp @@ -196,7 +196,7 @@ private: uORB::Subscription _sub_vehicle_command{ORB_ID(vehicle_command)}; /**< topic handle on which commands are received */ - uORB::PublicationQueued _pub_vehicle_command_ack{ORB_ID(vehicle_command_ack)}; + uORB::Publication _pub_vehicle_command_ack{ORB_ID(vehicle_command_ack)}; int _initTask(FlightTaskIndex task_index); }; diff --git a/src/lib/mixer_module/mixer_module.cpp b/src/lib/mixer_module/mixer_module.cpp index ca2eea4985..be8a1524a5 100644 --- a/src/lib/mixer_module/mixer_module.cpp +++ b/src/lib/mixer_module/mixer_module.cpp @@ -72,7 +72,7 @@ _control_latency_perf(perf_alloc(PC_ELAPSED, "control latency")) // Enforce the existence of the test_motor topic, so we won't miss initial publications test_motor_s test{}; - uORB::PublicationQueued test_motor_pub{ORB_ID(test_motor)}; + uORB::Publication test_motor_pub{ORB_ID(test_motor)}; test_motor_pub.publish(test); _motor_test.test_motor_sub.subscribe(); } diff --git a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp index f937e63a76..1d2e77c9cb 100644 --- a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp +++ b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp @@ -86,7 +86,7 @@ static void arm_auth_request_msg_send() vcmd.command = vehicle_command_s::VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST; vcmd.target_system = arm_parameters.struct_value.authorizer_system_id; - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; vcmd_pub.publish(vcmd); } diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 12c1b2d66a..64a90636cc 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -115,7 +115,7 @@ static struct vehicle_status_flags_s status_flags = {}; void *commander_low_prio_loop(void *arg); static void answer_command(const vehicle_command_s &cmd, unsigned result, - uORB::PublicationQueued &command_ack_pub); + uORB::Publication &command_ack_pub); #if defined(BOARD_HAS_POWER_CONTROL) static orb_advert_t power_button_state_pub = nullptr; @@ -184,7 +184,7 @@ static bool send_vehicle_command(uint16_t cmd, float param1 = NAN, float param2 vcmd.timestamp = hrt_absolute_time(); - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; return vcmd_pub.publish(vcmd); } @@ -532,7 +532,7 @@ Commander::Commander() : bool Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_s &cmd, actuator_armed_s *armed_local, - uORB::PublicationQueued &command_ack_pub) + uORB::Publication &command_ack_pub) { /* only handle commands that are meant to be handled by this system and component */ if (cmd.target_system != status_local->system_id || ((cmd.target_component != status_local->component_id) @@ -3377,7 +3377,7 @@ Commander::print_reject_arm(const char *msg) } void answer_command(const vehicle_command_s &cmd, unsigned result, - uORB::PublicationQueued &command_ack_pub) + uORB::Publication &command_ack_pub) { switch (result) { case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED: @@ -3425,7 +3425,7 @@ void *commander_low_prio_loop(void *arg) int cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); /* command ack */ - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; /* wakeup source(s) */ px4_pollfd_struct_t fds[1]; diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index e79c8ac03c..a80596d9cd 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -140,7 +140,7 @@ private: void estimator_check(const vehicle_status_flags_s &status_flags); bool handle_command(vehicle_status_s *status, const vehicle_command_s &cmd, actuator_armed_s *armed, - uORB::PublicationQueued &command_ack_pub); + uORB::Publication &command_ack_pub); unsigned handle_command_motor_test(const vehicle_command_s &cmd); @@ -420,7 +420,7 @@ private: uORB::PublicationData _home_pub{ORB_ID(home_position)}; - uORB::PublicationQueued _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; }; diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp index 6e5ef47f7c..689aa521e7 100644 --- a/src/modules/commander/calibration_routines.cpp +++ b/src/modules/commander/calibration_routines.cpp @@ -614,7 +614,7 @@ bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, const hrt_abstime &ca command_ack.target_component = cmd.source_component; command_ack.timestamp = hrt_absolute_time(); - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; command_ack_pub.publish(command_ack); return ret; diff --git a/src/modules/events/rc_loss_alarm.h b/src/modules/events/rc_loss_alarm.h index 2e106b74e5..861ced0511 100644 --- a/src/modules/events/rc_loss_alarm.h +++ b/src/modules/events/rc_loss_alarm.h @@ -65,7 +65,7 @@ private: /** Publish tune control to interrupt any sound */ void stop_tune(); - uORB::PublicationQueued _tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication _tune_control_pub{ORB_ID(tune_control)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; bool _was_armed = false; diff --git a/src/modules/events/send_event.cpp b/src/modules/events/send_event.cpp index 88833d4591..bc92d44117 100644 --- a/src/modules/events/send_event.cpp +++ b/src/modules/events/send_event.cpp @@ -126,7 +126,7 @@ void SendEvent::answer_command(const vehicle_command_s &cmd, unsigned result) command_ack.target_system = cmd.source_system; command_ack.target_component = cmd.source_component; - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; command_ack_pub.publish(command_ack); } diff --git a/src/modules/events/status_display.h b/src/modules/events/status_display.h index be3e6d062b..f70ce1006d 100644 --- a/src/modules/events/status_display.h +++ b/src/modules/events/status_display.h @@ -97,7 +97,7 @@ private: int _old_nav_state = -1; int _old_battery_status_warning = -1; - uORB::PublicationQueued _led_control_pub{ORB_ID(led_control)}; + uORB::Publication _led_control_pub{ORB_ID(led_control)}; }; diff --git a/src/modules/load_mon/LoadMon.hpp b/src/modules/load_mon/LoadMon.hpp index 1aa6411135..d1d66153b7 100644 --- a/src/modules/load_mon/LoadMon.hpp +++ b/src/modules/load_mon/LoadMon.hpp @@ -87,7 +87,7 @@ private: int _stack_task_index{0}; - uORB::PublicationQueued _task_stack_info_pub{ORB_ID(task_stack_info)}; + uORB::Publication _task_stack_info_pub{ORB_ID(task_stack_info)}; #endif uORB::Publication _cpuload_pub {ORB_ID(cpuload)}; diff --git a/src/modules/logger/log_writer_mavlink.h b/src/modules/logger/log_writer_mavlink.h index c80a549623..ad6d80fa3b 100644 --- a/src/modules/logger/log_writer_mavlink.h +++ b/src/modules/logger/log_writer_mavlink.h @@ -77,7 +77,7 @@ private: int publish_message(); ulog_stream_s _ulog_stream_data{}; - uORB::PublicationQueued _ulog_stream_pub{ORB_ID(ulog_stream)}; + uORB::Publication _ulog_stream_pub{ORB_ID(ulog_stream)}; int _ulog_stream_ack_sub{-1}; bool _need_reliable_transfer{false}; bool _is_started{false}; diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 1735bdd0a5..ca86b2c2e1 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1971,7 +1971,7 @@ void Logger::ack_vehicle_command(vehicle_command_s *cmd, uint32_t result) vehicle_command_ack.target_system = cmd->source_system; vehicle_command_ack.target_component = cmd->source_component; - uORB::PublicationQueued cmd_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication cmd_ack_pub{ORB_ID(vehicle_command_ack)}; cmd_ack_pub.publish(vehicle_command_ack); } diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 566dd0dc74..4b92d0c64b 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2149,7 +2149,7 @@ Mavlink::task_main(int argc, char *argv[]) uORB::Subscription ack_sub{ORB_ID(vehicle_command_ack)}; /* command ack */ - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; uORB::Subscription mavlink_log_sub{ORB_ID(mavlink_log)}; diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index 04dec46b2a..140c8973d3 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -128,7 +128,7 @@ protected: uORB::Publication _rc_param_map_pub{ORB_ID(rc_parameter_map)}; rc_parameter_map_s _rc_param_map{}; - uORB::PublicationQueued _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)}; + uORB::Publication _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)}; // enforce ORB_ID(uavcan_parameter_request) constants that map to MAVLINK defines static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ == MAVLINK_MSG_ID_PARAM_REQUEST_READ, "uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_READ constant mismatch"); diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 9873d7a9a8..1bab8ee272 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -283,10 +283,10 @@ private: uORB::PublicationMulti _radio_status_pub{ORB_ID(radio_status)}; // ORB publications (queue length > 1) - uORB::PublicationQueued _gps_inject_data_pub{ORB_ID(gps_inject_data)}; - uORB::PublicationQueued _transponder_report_pub{ORB_ID(transponder_report)}; - uORB::PublicationQueued _cmd_ack_pub{ORB_ID(vehicle_command_ack)}; - uORB::PublicationQueued _cmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication _gps_inject_data_pub{ORB_ID(gps_inject_data)}; + uORB::Publication _transponder_report_pub{ORB_ID(transponder_report)}; + uORB::Publication _cmd_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _cmd_pub{ORB_ID(vehicle_command)}; // ORB subscriptions uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; diff --git a/src/modules/mavlink/tune_publisher.h b/src/modules/mavlink/tune_publisher.h index 4ec2fa3b65..ea1ff449f1 100644 --- a/src/modules/mavlink/tune_publisher.h +++ b/src/modules/mavlink/tune_publisher.h @@ -51,5 +51,5 @@ private: char _tune_buffer[MAX_TUNE_LEN] {0}; hrt_abstime _next_publish_time {0}; - uORB::PublicationQueued _tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication _tune_control_pub{ORB_ID(tune_control)}; }; diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.hpp b/src/modules/mc_pos_control/MulticopterPositionControl.hpp index a1fca96374..efb4336863 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.hpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.hpp @@ -101,7 +101,7 @@ private: Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */ uORB::Publication _vehicle_attitude_setpoint_pub; - uORB::PublicationQueued _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command publication */ + uORB::Publication _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command publication */ orb_advert_t _mavlink_log_pub{nullptr}; uORB::Publication _landing_gear_pub{ORB_ID(landing_gear)}; diff --git a/src/modules/muorb/test/muorb_test_example.cpp b/src/modules/muorb/test/muorb_test_example.cpp index 74731017f4..8cb9804c78 100644 --- a/src/modules/muorb/test/muorb_test_example.cpp +++ b/src/modules/muorb/test/muorb_test_example.cpp @@ -62,7 +62,7 @@ int MuorbTestExample::DefaultTest() int i = 0; uORB::Subscription sub_vc{ORB_ID(vehicle_command)}; - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; uORB::Publication pub_id{ORB_ID(esc_status)}; pub_id.publish(m_esc_status); @@ -103,7 +103,7 @@ int MuorbTestExample::DefaultTest() int MuorbTestExample::PingPongTest() { int i = 0; - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; uORB::Subscription sub_esc_status{ORB_ID(esc_status)}; while (!appState.exitRequested()) { diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index b3b61002e1..31b86237e5 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -343,8 +343,8 @@ private: orb_advert_t _mavlink_log_pub{nullptr}; /**< the uORB advert to send messages over mavlink */ - uORB::PublicationQueued _vehicle_cmd_ack_pub{ORB_ID(vehicle_command_ack)}; - uORB::PublicationQueued _vehicle_cmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication _vehicle_cmd_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _vehicle_cmd_pub{ORB_ID(vehicle_command)}; // Subscriptions home_position_s _home_pos{}; /**< home position for RTL */ diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 142f732c80..2277ff23c7 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1006,7 +1006,7 @@ void Navigator::fake_traffic(const char *callsign, float distance, float directi #endif /* BOARD_HAS_NO_UUID */ - uORB::PublicationQueued tr_pub{ORB_ID(transponder_report)}; + uORB::Publication tr_pub{ORB_ID(transponder_report)}; tr_pub.publish(tr); } diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index 2efbc41107..1ecd1f1c07 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -188,7 +188,7 @@ private: uORB::Publication _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)}; uORB::Publication _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)}; - uORB::PublicationQueued _command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; uORB::PublicationMulti *_dist_pubs[RANGE_FINDER_MAX_SENSORS] {}; uint8_t _dist_sensor_ids[RANGE_FINDER_MAX_SENSORS] {}; diff --git a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp index 97030b75db..4c6181e224 100644 --- a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp +++ b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp @@ -225,7 +225,7 @@ void TemperatureCompensationModule::Run() command_ack.target_system = cmd.source_system; command_ack.target_component = cmd.source_component; - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; command_ack_pub.publish(command_ack); } } @@ -344,7 +344,7 @@ int TemperatureCompensationModule::custom_command(int argc, char *argv[]) || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN); vcmd.command = vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION; - uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; + uORB::Publication vcmd_pub{ORB_ID(vehicle_command)}; vcmd_pub.publish(vcmd); return PX4_OK; diff --git a/src/modules/temperature_compensation/temperature_calibration/task.cpp b/src/modules/temperature_compensation/temperature_calibration/task.cpp index 61ab722010..049324c176 100644 --- a/src/modules/temperature_compensation/temperature_calibration/task.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/task.cpp @@ -87,7 +87,7 @@ public: private: void publish_led_control(led_control_s &led_control); - uORB::PublicationQueued _led_control_pub{ORB_ID(led_control)}; + uORB::Publication _led_control_pub{ORB_ID(led_control)}; bool _force_task_exit = false; int _control_task = -1; // task handle for task diff --git a/src/modules/uORB/Publication.hpp b/src/modules/uORB/Publication.hpp index 0f2256af0a..bb95f21334 100644 --- a/src/modules/uORB/Publication.hpp +++ b/src/modules/uORB/Publication.hpp @@ -163,10 +163,4 @@ private: T _data{}; }; - -template -using PublicationQueued = Publication; - - - } // namespace uORB diff --git a/src/modules/uORB/PublicationMulti.hpp b/src/modules/uORB/PublicationMulti.hpp index b4aafe4e9a..9ef37cd0a7 100644 --- a/src/modules/uORB/PublicationMulti.hpp +++ b/src/modules/uORB/PublicationMulti.hpp @@ -122,8 +122,4 @@ private: T _data{}; }; - -template -using PublicationQueuedMulti = PublicationMulti; - } // namespace uORB diff --git a/src/modules/vmount/input_mavlink.cpp b/src/modules/vmount/input_mavlink.cpp index 80fcb04ce4..570dd2d086 100644 --- a/src/modules/vmount/input_mavlink.cpp +++ b/src/modules/vmount/input_mavlink.cpp @@ -369,7 +369,7 @@ void InputMavlinkCmdMount::_ack_vehicle_command(vehicle_command_s *cmd) vehicle_command_ack.target_system = cmd->source_system; vehicle_command_ack.target_component = cmd->source_component; - uORB::PublicationQueued cmd_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication cmd_ack_pub{ORB_ID(vehicle_command_ack)}; cmd_ack_pub.publish(vehicle_command_ack); } diff --git a/src/modules/vmount/output_mavlink.h b/src/modules/vmount/output_mavlink.h index 7a7fde5579..5ace7f6582 100644 --- a/src/modules/vmount/output_mavlink.h +++ b/src/modules/vmount/output_mavlink.h @@ -62,7 +62,7 @@ public: private: - uORB::PublicationQueued _vehicle_command_pub{ORB_ID(vehicle_command)}; + uORB::Publication _vehicle_command_pub{ORB_ID(vehicle_command)}; }; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index b003b01908..0a745f211d 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -183,7 +183,7 @@ VtolAttitudeControl::handle_command() command_ack.target_system = _vehicle_cmd.source_system; command_ack.target_component = _vehicle_cmd.source_component; - uORB::PublicationQueued command_ack_pub{ORB_ID(vehicle_command_ack)}; + uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; command_ack_pub.publish(command_ack); } } diff --git a/src/systemcmds/failure/failure.cpp b/src/systemcmds/failure/failure.cpp index 6c8a6d86d0..32fae7ba6f 100644 --- a/src/systemcmds/failure/failure.cpp +++ b/src/systemcmds/failure/failure.cpp @@ -124,7 +124,7 @@ int inject_failure(uint8_t unit, uint8_t type, uint8_t instance) uORB::Subscription command_ack_sub{ORB_ID(vehicle_command_ack)}; - uORB::PublicationQueued command_pub{ORB_ID(vehicle_command)}; + uORB::Publication command_pub{ORB_ID(vehicle_command)}; vehicle_command_s command{}; command.command = vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE; diff --git a/src/systemcmds/led_control/led_control.cpp b/src/systemcmds/led_control/led_control.cpp index f60625889d..7b54e82892 100644 --- a/src/systemcmds/led_control/led_control.cpp +++ b/src/systemcmds/led_control/led_control.cpp @@ -58,7 +58,7 @@ static void publish_led_control(led_control_s &led_control) { led_control.timestamp = hrt_absolute_time(); - uORB::PublicationQueued led_control_pub{ORB_ID(led_control)}; + uORB::Publication led_control_pub{ORB_ID(led_control)}; led_control_pub.publish(led_control); } diff --git a/src/systemcmds/motor_test/motor_test.cpp b/src/systemcmds/motor_test/motor_test.cpp index 67fe416ebe..af7d3858a8 100644 --- a/src/systemcmds/motor_test/motor_test.cpp +++ b/src/systemcmds/motor_test/motor_test.cpp @@ -61,7 +61,7 @@ void motor_test(unsigned channel, float value, uint8_t driver_instance, int time test_motor.driver_instance = driver_instance; test_motor.timeout_ms = timeout_ms; - uORB::PublicationQueued test_motor_pub{ORB_ID(test_motor)}; + uORB::Publication test_motor_pub{ORB_ID(test_motor)}; test_motor_pub.publish(test_motor); if (test_motor.action == test_motor_s::ACTION_STOP) { diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp index 0a677e45ba..dc85e446f2 100644 --- a/src/systemcmds/tune_control/tune_control.cpp +++ b/src/systemcmds/tune_control/tune_control.cpp @@ -60,7 +60,7 @@ static void usage(); static void publish_tune_control(tune_control_s &tune_control) { - uORB::PublicationQueued tune_control_pub{ORB_ID(tune_control)}; + uORB::Publication tune_control_pub{ORB_ID(tune_control)}; tune_control.timestamp = hrt_absolute_time(); tune_control_pub.publish(tune_control); }