diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index c59b97a97296..f672ae99581b 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -270,7 +270,7 @@ class MD25 : public device::I2C struct pollfd _controlPoll; /** actuator controls subscription */ - uORB::Subscription _actuators; + uORB::SubscriptionData _actuators; // local copy of data from i2c device uint8_t _version; diff --git a/src/examples/segway/blocks.hpp b/src/examples/segway/blocks.hpp index ed58677f2220..42c073cbb538 100644 --- a/src/examples/segway/blocks.hpp +++ b/src/examples/segway/blocks.hpp @@ -94,13 +94,13 @@ class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock // subscriptions uORB::SubscriptionPolled _att; - uORB::Subscription _manual; - uORB::Subscription _param_update; - uORB::Subscription _missionCmd; - uORB::Subscription _attCmd; - uORB::Subscription _pos; - uORB::Subscription _ratesCmd; - uORB::Subscription _status; + uORB::SubscriptionData _manual; + uORB::SubscriptionData _param_update; + uORB::SubscriptionData _missionCmd; + uORB::SubscriptionData _attCmd; + uORB::SubscriptionData _pos; + uORB::SubscriptionData _ratesCmd; + uORB::SubscriptionData _status; // publications uORB::Publication _actuators; diff --git a/src/lib/CollisionPrevention/CollisionPrevention.hpp b/src/lib/CollisionPrevention/CollisionPrevention.hpp index 7689fdd845b4..6eb62f9a23de 100644 --- a/src/lib/CollisionPrevention/CollisionPrevention.hpp +++ b/src/lib/CollisionPrevention/CollisionPrevention.hpp @@ -77,7 +77,7 @@ class CollisionPrevention : public ModuleParams orb_advert_t _constraints_pub{nullptr}; /**< constraints publication */ orb_advert_t _mavlink_log_pub{nullptr}; /**< Mavlink log uORB handle */ - uORB::Subscription *_sub_obstacle_distance{nullptr}; /**< obstacle distances received form a range sensor */ + uORB::SubscriptionData *_sub_obstacle_distance{nullptr}; /**< obstacle distances received form a range sensor */ static constexpr uint64_t RANGE_STREAM_TIMEOUT_US = 500000; static constexpr uint64_t MESSAGE_THROTTLE_US = 5000000; diff --git a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp index 104cdb2a55ee..b25ef08ee596 100644 --- a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp +++ b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp @@ -97,7 +97,7 @@ class FlightTaskAuto : public FlightTask matrix::Vector3f _next_wp{}; /**< The next waypoint after target (local frame). If no next setpoint is available, next is set to target. */ float _mc_cruise_speed{0.0f}; /**< Requested cruise speed. If not valid, default cruise speed is used. */ WaypointType _type{WaypointType::idle}; /**< Type of current target triplet. */ - uORB::Subscription *_sub_home_position{nullptr}; + uORB::SubscriptionData *_sub_home_position{nullptr}; State _current_state{State::none}; float _target_acceptance_radius = 0.0f; /**< Acceptances radius of the target */ @@ -117,8 +117,8 @@ class FlightTaskAuto : public FlightTask private: matrix::Vector2f _lock_position_xy{NAN, NAN}; /**< if no valid triplet is received, lock positition to current position */ bool _yaw_lock = false; /**< if within acceptance radius, lock yaw to current yaw */ - uORB::Subscription *_sub_triplet_setpoint{nullptr}; - uORB::Subscription *_sub_vehicle_status{nullptr}; + uORB::SubscriptionData *_sub_triplet_setpoint{nullptr}; + uORB::SubscriptionData *_sub_vehicle_status{nullptr}; matrix::Vector3f _triplet_target; /**< current triplet from navigator which may differ from the intenal one (_target) depending on the vehicle state. */ diff --git a/src/lib/FlightTasks/tasks/FlightTask/FlightTask.hpp b/src/lib/FlightTasks/tasks/FlightTask/FlightTask.hpp index 7e15cd9d3275..19efa61bf1f5 100644 --- a/src/lib/FlightTasks/tasks/FlightTask/FlightTask.hpp +++ b/src/lib/FlightTasks/tasks/FlightTask/FlightTask.hpp @@ -173,8 +173,8 @@ class FlightTask : public ModuleParams protected: - uORB::Subscription *_sub_vehicle_local_position{nullptr}; - uORB::Subscription *_sub_attitude{nullptr}; + uORB::SubscriptionData *_sub_vehicle_local_position{nullptr}; + uORB::SubscriptionData *_sub_attitude{nullptr}; uint8_t _heading_reset_counter{0}; /**< estimator heading reset */ /** diff --git a/src/lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp b/src/lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp index c02de4f02b4a..df941c997518 100644 --- a/src/lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp +++ b/src/lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp @@ -57,7 +57,7 @@ class SubscriptionArray * @return true on success, false otherwise (subscription set to nullptr) */ template - bool get(const struct orb_metadata *meta, uORB::Subscription *&subscription, unsigned instance = 0); + bool get(const struct orb_metadata *meta, uORB::SubscriptionData *&subscription, unsigned instance = 0); /** * update all subscriptions (if new data is available) @@ -81,13 +81,14 @@ class SubscriptionArray template -bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::Subscription *&subscription, unsigned instance) +bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::SubscriptionData *&subscription, + unsigned instance) { // does it already exist? for (int i = 0; i < _subscriptions_count; ++i) { if (_subscriptions[i]->get_topic() == meta && _subscriptions[i]->get_instance() == instance) { // we know the type must be correct, so we can use reinterpret_cast (dynamic_cast is not available) - subscription = reinterpret_cast*>(_subscriptions[i]); + subscription = reinterpret_cast*>(_subscriptions[i]); return true; } } @@ -100,7 +101,7 @@ bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::Subscription< } } - subscription = new uORB::Subscription(meta, 0, instance); + subscription = new uORB::SubscriptionData(meta, 0, instance); if (!subscription) { return false; diff --git a/src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp b/src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp index 7fb49a75bbf0..3e77ff034f75 100644 --- a/src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp +++ b/src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp @@ -68,7 +68,7 @@ class FlightTaskManual : public FlightTask bool _evaluateSticks(); /**< checks and sets stick inputs */ void _applyGearSwitch(uint8_t gswitch); /**< Sets gears according to switch */ - uORB::Subscription *_sub_manual_control_setpoint{nullptr}; + uORB::SubscriptionData *_sub_manual_control_setpoint{nullptr}; DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask, (ParamFloat) _param_mpc_hold_dz, /**< 0-deadzone around the center for the sticks */ diff --git a/src/lib/FlightTasks/tasks/ManualAltitude/FlightTaskManualAltitude.hpp b/src/lib/FlightTasks/tasks/ManualAltitude/FlightTaskManualAltitude.hpp index 2993f4d38f73..e7c9f74a0cd2 100644 --- a/src/lib/FlightTasks/tasks/ManualAltitude/FlightTaskManualAltitude.hpp +++ b/src/lib/FlightTasks/tasks/ManualAltitude/FlightTaskManualAltitude.hpp @@ -109,7 +109,7 @@ class FlightTaskManualAltitude : public FlightTaskManual */ void _respectGroundSlowdown(); - uORB::Subscription *_sub_home_position{nullptr}; + uORB::SubscriptionData *_sub_home_position{nullptr}; uint8_t _reset_counter = 0; /**< counter for estimator resets in z-direction */ float _max_speed_up = 10.0f; diff --git a/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.hpp b/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.hpp index c1a1e8179160..6acaf8c74989 100644 --- a/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.hpp +++ b/src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.hpp @@ -53,7 +53,7 @@ class FlightTaskOffboard : public FlightTask bool updateInitialize() override; protected: - uORB::Subscription *_sub_triplet_setpoint{nullptr}; + uORB::SubscriptionData *_sub_triplet_setpoint{nullptr}; private: matrix::Vector3f _position_lock{}; diff --git a/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp b/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp index 8de317c8529a..cceef4486d0a 100644 --- a/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp +++ b/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp @@ -102,8 +102,8 @@ class ObstacleAvoidance : public ModuleParams private: - uORB::Subscription *_sub_vehicle_trajectory_waypoint{nullptr}; /**< vehicle trajectory waypoint subscription */ - uORB::Subscription *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */ + uORB::SubscriptionData *_sub_vehicle_trajectory_waypoint{nullptr}; /**< vehicle trajectory waypoint subscription */ + uORB::SubscriptionData *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */ DEFINE_PARAMETERS( (ParamInt) COM_OBS_AVOID, /**< obstacle avoidance enabled */ diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 36700da6dcff..fc0f39e65dd8 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -59,8 +59,6 @@ #include #include using math::constrain; -using uORB::Publication; -using uORB::Subscription; using namespace time_literals; @@ -206,12 +204,13 @@ class Commander : public ModuleBase, public ModuleParams bool _print_avoidance_msg_once{false}; // Subscriptions - Subscription _estimator_status_sub{ORB_ID(estimator_status)}; - Subscription _mission_result_sub{ORB_ID(mission_result)}; - Subscription _global_position_sub{ORB_ID(vehicle_global_position)}; - Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::SubscriptionData _estimator_status_sub{ORB_ID(estimator_status)}; + uORB::SubscriptionData _mission_result_sub{ORB_ID(mission_result)}; + uORB::SubscriptionData _global_position_sub{ORB_ID(vehicle_global_position)}; + uORB::SubscriptionData _local_position_sub{ORB_ID(vehicle_local_position)}; - Publication _home_pub{ORB_ID(home_position)}; + // Publications + uORB::Publication _home_pub{ORB_ID(home_position)}; orb_advert_t _status_pub{nullptr}; }; diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp index 26afdbade127..ada6fcf14a0a 100644 --- a/src/modules/commander/PreflightCheck.cpp +++ b/src/modules/commander/PreflightCheck.cpp @@ -109,7 +109,7 @@ static bool magnometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &sta if (exists) { - uORB::Subscription magnetometer{ORB_ID(sensor_mag), 0, instance}; + uORB::SubscriptionData magnetometer{ORB_ID(sensor_mag), 0, instance}; mag_valid = (hrt_elapsed_time(&magnetometer.get().timestamp) < 1_s); @@ -245,7 +245,7 @@ static bool accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s & if (exists) { - uORB::Subscription accel{ORB_ID(sensor_accel), 0, instance}; + uORB::SubscriptionData accel{ORB_ID(sensor_accel), 0, instance}; accel_valid = (hrt_elapsed_time(&accel.get().timestamp) < 1_s); @@ -309,7 +309,7 @@ static bool gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, u if (exists) { - uORB::Subscription gyro{ORB_ID(sensor_gyro), 0, instance}; + uORB::SubscriptionData gyro{ORB_ID(sensor_gyro), 0, instance}; gyro_valid = (hrt_elapsed_time(&gyro.get().timestamp) < 1_s); @@ -352,7 +352,7 @@ static bool baroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, u bool baro_valid = false; if (exists) { - uORB::Subscription baro{ORB_ID(sensor_baro), 0, instance}; + uORB::SubscriptionData baro{ORB_ID(sensor_baro), 0, instance}; baro_valid = (hrt_elapsed_time(&baro.get().timestamp) < 1_s); diff --git a/src/modules/commander/failure_detector/FailureDetector.hpp b/src/modules/commander/failure_detector/FailureDetector.hpp index c354effde6f9..fb5a9eb68272 100644 --- a/src/modules/commander/failure_detector/FailureDetector.hpp +++ b/src/modules/commander/failure_detector/FailureDetector.hpp @@ -60,7 +60,7 @@ typedef enum { FAILURE_ALT = vehicle_status_s::FAILURE_ALT, } failure_detector_bitmak; -using uORB::Subscription; +using uORB::SubscriptionData; class FailureDetector : public ModuleParams { @@ -79,8 +79,8 @@ class FailureDetector : public ModuleParams ) // Subscriptions - Subscription _sub_vehicle_attitude_setpoint; - Subscription _sub_vehicule_attitude; + SubscriptionData _sub_vehicle_attitude_setpoint; + SubscriptionData _sub_vehicule_attitude; uint8_t _status{FAILURE_NONE}; diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 0867b6390036..8c8ccbad7f90 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -65,7 +65,7 @@ using matrix::Eulerf; using matrix::Quatf; -using uORB::Subscription; +using uORB::SubscriptionData; class FixedwingAttitudeControl final : public ModuleBase { @@ -123,7 +123,7 @@ class FixedwingAttitudeControl final : public ModuleBase _airspeed_sub; + SubscriptionData _airspeed_sub; perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */ diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp index 44a9d537848a..3229e4a67376 100644 --- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp @@ -99,7 +99,7 @@ using matrix::Vector2f; using matrix::Vector3f; using matrix::wrap_pi; -using uORB::Subscription; +using uORB::SubscriptionData; using namespace launchdetection; using namespace runwaytakeoff; @@ -181,8 +181,8 @@ class FixedwingPositionControl final : public ModuleBase _sub_airspeed; - Subscription _sub_sensors; + SubscriptionData _sub_airspeed; + SubscriptionData _sub_sensors; perf_counter_t _loop_perf; ///< loop performance counter */ diff --git a/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp b/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp index cd910422a0c9..d1b6b60e9380 100644 --- a/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp +++ b/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp @@ -67,7 +67,7 @@ using matrix::Dcmf; -using uORB::Subscription; +using uORB::SubscriptionData; class GroundRoverPositionControl { @@ -110,8 +110,8 @@ class GroundRoverPositionControl vehicle_control_mode_s _control_mode{}; /**< control mode */ vehicle_global_position_s _global_pos{}; /**< global vehicle position */ - Subscription _sub_attitude; - Subscription _sub_sensors; + SubscriptionData _sub_attitude; + SubscriptionData _sub_sensors; perf_counter_t _loop_perf; /**< loop performance counter */ diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 82e361c2e0c5..fcb888732f68 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -210,7 +210,7 @@ void BlockLocalPositionEstimator::update() if (!armedState && (_sub_lidar == nullptr || _sub_sonar == nullptr)) { // detect distance sensors for (size_t i = 0; i < N_DIST_SUBS; i++) { - uORB::Subscription *s = _dist_subs[i]; + uORB::SubscriptionData *s = _dist_subs[i]; if (s == _sub_lidar || s == _sub_sonar) { continue; } diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp index 141470a3f6bc..e57f9474e446 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp @@ -250,21 +250,21 @@ class BlockLocalPositionEstimator : public control::SuperBlock, public ModulePar uORB::SubscriptionPolled _sub_param_update; uORB::SubscriptionPolled _sub_sensor; - uORB::Subscription _sub_armed; - uORB::Subscription _sub_land; - uORB::Subscription _sub_att; - uORB::Subscription _sub_gps; - uORB::Subscription _sub_visual_odom; - uORB::Subscription _sub_mocap_odom; - uORB::Subscription _sub_dist0; - uORB::Subscription _sub_dist1; - uORB::Subscription _sub_dist2; - uORB::Subscription _sub_dist3; - uORB::Subscription *_dist_subs[N_DIST_SUBS]; - uORB::Subscription *_sub_lidar; - uORB::Subscription *_sub_sonar; - uORB::Subscription _sub_landing_target_pose; - uORB::Subscription _sub_airdata; + uORB::SubscriptionData _sub_armed; + uORB::SubscriptionData _sub_land; + uORB::SubscriptionData _sub_att; + uORB::SubscriptionData _sub_gps; + uORB::SubscriptionData _sub_visual_odom; + uORB::SubscriptionData _sub_mocap_odom; + uORB::SubscriptionData _sub_dist0; + uORB::SubscriptionData _sub_dist1; + uORB::SubscriptionData _sub_dist2; + uORB::SubscriptionData _sub_dist3; + uORB::SubscriptionData *_dist_subs[N_DIST_SUBS]; + uORB::SubscriptionData *_sub_lidar; + uORB::SubscriptionData *_sub_sonar; + uORB::SubscriptionData _sub_landing_target_pose; + uORB::SubscriptionData _sub_airdata; // publications uORB::Publication _pub_lpos; diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 47595723301d..f001d2921671 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -868,7 +868,7 @@ void Logger::run() } int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); - uORB::Subscription parameter_update_sub(ORB_ID(parameter_update)); + uORB::SubscriptionData parameter_update_sub(ORB_ID(parameter_update)); int log_message_sub = orb_subscribe(ORB_ID(log_message)); orb_set_interval(log_message_sub, 20); diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 5f66459a5a24..e35b457b46e3 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -633,7 +633,7 @@ Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_cont /* if this is a config link, stay here and wait for it to open */ if (_uart_fd < 0 && _mode == MAVLINK_MODE_CONFIG) { - uORB::Subscription armed_sub{ORB_ID(actuator_armed)}; + uORB::SubscriptionData armed_sub{ORB_ID(actuator_armed)}; /* get the system arming state and abort on arming */ while (_uart_fd < 0) { diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index cdef98e5b214..28952a5d8f5f 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -125,7 +125,7 @@ class MavlinkMissionManager static bool _transfer_in_progress; ///< Global variable checking for current transmission - uORB::SubscriptionBase _mission_result_sub{ORB_ID(mission_result)}; + uORB::Subscription _mission_result_sub{ORB_ID(mission_result)}; orb_advert_t _offboard_mission_pub{nullptr}; diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h index ef1d83e2aeda..17948f8ccc38 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.h +++ b/src/modules/mavlink/mavlink_orb_subscription.h @@ -93,7 +93,7 @@ class MavlinkOrbSubscription : public ListNode private: - uORB::SubscriptionBase _sub; + uORB::Subscription _sub; }; diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 97800311bc3c..cd69daa83eaf 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -248,9 +248,9 @@ class MavlinkReceiver static constexpr int _gps_inject_data_queue_size{6}; - uORB::SubscriptionBase _actuator_armed_sub{ORB_ID(actuator_armed)}; - uORB::SubscriptionBase _control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::SubscriptionBase _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; + uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; + uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; int _orb_class_instance{-1}; diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h index f9ed6f8ac43c..35d20f9b2d52 100644 --- a/src/modules/navigator/geofence.h +++ b/src/modules/navigator/geofence.h @@ -166,7 +166,7 @@ class Geofence : public ModuleParams (ParamFloat) _param_gf_max_ver_dist ) - uORB::Subscription _sub_airdata; + uORB::SubscriptionData _sub_airdata; int _outside_counter{0}; uint16_t _update_counter{0}; ///< dataman update counter: if it does not match, we polygon data was updated diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index f4f084321cd2..62be756398bd 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -450,7 +450,7 @@ MissionFeasibilityChecker::checkFixedWingLanding(const mission_s &mission, bool if (MissionBlock::item_contains_position(missionitem_previous)) { - uORB::Subscription landing_status{ORB_ID(position_controller_landing_status)}; + uORB::SubscriptionData landing_status{ORB_ID(position_controller_landing_status)}; landing_status.forcedUpdate(); const bool landing_status_valid = (landing_status.get().timestamp > 0); diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 1e7afae7c6f8..b0dec7e89ab1 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -320,7 +320,7 @@ class Navigator : public ModuleBase, public ModuleParams vehicle_local_position_s _local_pos{}; /**< local vehicle position */ vehicle_status_s _vstatus{}; /**< vehicle status */ - uORB::Subscription _position_controller_status_sub{ORB_ID(position_controller_status)}; + uORB::SubscriptionData _position_controller_status_sub{ORB_ID(position_controller_status)}; uint8_t _previous_nav_state{}; /**< nav_state of the previous iteration*/ diff --git a/src/modules/sensors/voted_sensors_update.cpp b/src/modules/sensors/voted_sensors_update.cpp index 597313ebbab4..612c88c67d3a 100644 --- a/src/modules/sensors/voted_sensors_update.cpp +++ b/src/modules/sensors/voted_sensors_update.cpp @@ -152,9 +152,9 @@ void VotedSensorsUpdate::parameters_update() _temperature_compensation.parameters_update(_hil_enabled); /* gyro */ - for (int topic_instance = 0; topic_instance < _gyro.subscription_count; ++topic_instance) { + for (uint8_t topic_instance = 0; topic_instance < _gyro.subscription_count; ++topic_instance) { - uORB::Subscription report{ORB_ID(sensor_gyro), 0, (unsigned)topic_instance}; + uORB::SubscriptionData report{ORB_ID(sensor_gyro), 0, topic_instance}; int temp = _temperature_compensation.set_sensor_id_gyro(report.get().device_id, topic_instance); @@ -172,9 +172,9 @@ void VotedSensorsUpdate::parameters_update() /* accel */ - for (int topic_instance = 0; topic_instance < _accel.subscription_count; ++topic_instance) { + for (uint8_t topic_instance = 0; topic_instance < _accel.subscription_count; ++topic_instance) { - uORB::Subscription report{ORB_ID(sensor_accel), 0, (unsigned)topic_instance}; + uORB::SubscriptionData report{ORB_ID(sensor_accel), 0, topic_instance}; int temp = _temperature_compensation.set_sensor_id_accel(report.get().device_id, topic_instance); @@ -192,9 +192,9 @@ void VotedSensorsUpdate::parameters_update() /* baro */ - for (int topic_instance = 0; topic_instance < _baro.subscription_count; ++topic_instance) { + for (uint8_t topic_instance = 0; topic_instance < _baro.subscription_count; ++topic_instance) { - uORB::Subscription report{ORB_ID(sensor_baro), 0, (unsigned)topic_instance}; + uORB::SubscriptionData report{ORB_ID(sensor_baro), 0, topic_instance}; int temp = _temperature_compensation.set_sensor_id_baro(report.get().device_id, topic_instance); diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp index 669b3b1a55c0..edd82b7326e0 100644 --- a/src/modules/uORB/Subscription.cpp +++ b/src/modules/uORB/Subscription.cpp @@ -42,19 +42,19 @@ namespace uORB { -SubscriptionBase::SubscriptionBase(const orb_metadata *meta, uint8_t instance) : +Subscription::Subscription(const orb_metadata *meta, uint8_t instance) : _meta(meta), _instance(instance) { init(); } -SubscriptionBase::~SubscriptionBase() +Subscription::~Subscription() { unsubscribe(); } -bool SubscriptionBase::subscribe() +bool Subscription::subscribe() { DeviceMaster *device_master = uORB::Manager::get_instance()->get_device_master(); _node = device_master->getDeviceNode(_meta, _instance); @@ -74,7 +74,7 @@ bool SubscriptionBase::subscribe() return false; } -void SubscriptionBase::unsubscribe() +void Subscription::unsubscribe() { if (_node != nullptr) { _node->remove_internal_subscriber(); @@ -83,7 +83,7 @@ void SubscriptionBase::unsubscribe() _last_generation = 0; } -bool SubscriptionBase::init() +bool Subscription::init() { if (_meta != nullptr) { // this throttles the relatively expensive calls to getDeviceNode() @@ -100,7 +100,7 @@ bool SubscriptionBase::init() return false; } -bool SubscriptionBase::forceInit() +bool Subscription::forceInit() { if (_node == nullptr) { // reset generation to force subscription attempt @@ -111,7 +111,7 @@ bool SubscriptionBase::forceInit() return false; } -bool SubscriptionBase::set_topic(orb_metadata *meta) +bool Subscription::set_topic(orb_metadata *meta) { if (meta != _meta) { unsubscribe(); @@ -123,7 +123,7 @@ bool SubscriptionBase::set_topic(orb_metadata *meta) return false; } -bool SubscriptionBase::set_instance(uint8_t instance) +bool Subscription::set_instance(uint8_t instance) { if (instance != _instance) { unsubscribe(); @@ -134,7 +134,7 @@ bool SubscriptionBase::set_instance(uint8_t instance) return false; } -bool SubscriptionBase::update(uint64_t *time, void *dst) +bool Subscription::update(uint64_t *time, void *dst) { if (published()) { // always copy data diff --git a/src/modules/uORB/Subscription.hpp b/src/modules/uORB/Subscription.hpp index b590f9b2c290..48a99ca87f8a 100644 --- a/src/modules/uORB/Subscription.hpp +++ b/src/modules/uORB/Subscription.hpp @@ -54,7 +54,7 @@ namespace uORB * Base subscription wrapper class, used in list traversal * of various subscriptions. */ -class SubscriptionBase +class Subscription { public: @@ -65,9 +65,9 @@ class SubscriptionBase * macro) for the topic. * @param instance The instance for multi sub. */ - SubscriptionBase() = default; - SubscriptionBase(const orb_metadata *meta, uint8_t instance = 0); - virtual ~SubscriptionBase(); + Subscription() = default; + Subscription(const orb_metadata *meta, uint8_t instance = 0); + virtual ~Subscription(); bool valid() const { return _node != nullptr; } @@ -113,14 +113,14 @@ class SubscriptionBase }; // TODO: finish -class SubscriptionInterval : public SubscriptionBase +class SubscriptionInterval : public Subscription { public: SubscriptionInterval() = default; SubscriptionInterval(const orb_metadata *meta, unsigned interval = 0, uint8_t instance = 0) : - SubscriptionBase(meta, instance), + Subscription(meta, instance), _interval(interval) {} @@ -129,7 +129,7 @@ class SubscriptionInterval : public SubscriptionBase bool updated() override { if (hrt_absolute_time() >= (_last_update + (_interval * 1000))) { - return SubscriptionBase::updated(); + return Subscription::updated(); } return false; @@ -161,7 +161,7 @@ class SubscriptionInterval : public SubscriptionBase /** * alias class name so it is clear that the base class */ -typedef SubscriptionBase SubscriptionTiny; +typedef Subscription SubscriptionTiny; /** * The subscription base class as a list node. @@ -202,7 +202,7 @@ class SubscriptionNode : public SubscriptionInterval, public ListNode -class Subscription final : public SubscriptionNode +class SubscriptionData final : public SubscriptionNode { public: /** @@ -215,25 +215,25 @@ class Subscription final : public SubscriptionNode * @param list A list interface for adding to * list during construction */ - Subscription(const orb_metadata *meta, unsigned interval = 0, uint8_t instance = 0, - List *list = nullptr): + SubscriptionData(const orb_metadata *meta, unsigned interval = 0, uint8_t instance = 0, + List *list = nullptr): SubscriptionNode(meta, interval, instance, list) { forcedUpdate(); } - ~Subscription() override final = default; + ~SubscriptionData() override final = default; // no copy, assignment, move, move assignment - Subscription(const Subscription &) = delete; - Subscription &operator=(const Subscription &) = delete; - Subscription(Subscription &&) = delete; - Subscription &operator=(Subscription &&) = delete; + SubscriptionData(const SubscriptionData &) = delete; + SubscriptionData &operator=(const SubscriptionData &) = delete; + SubscriptionData(SubscriptionData &&) = delete; + SubscriptionData &operator=(SubscriptionData &&) = delete; /** * Create an update function that uses the embedded struct. */ - bool update() override final { return SubscriptionBase::update((void *)(&_data)); } + bool update() override final { return Subscription::update((void *)(&_data)); } bool forcedUpdate() override final { return copy(&_data); } @@ -295,10 +295,10 @@ class SubscriptionPolled } // no copy, assignment, move, move assignment - SubscriptionPolled(const SubscriptionBase &) = delete; - SubscriptionPolled &operator=(const SubscriptionBase &) = delete; - SubscriptionPolled(SubscriptionBase &&) = delete; - SubscriptionPolled &operator=(SubscriptionBase &&) = delete; + SubscriptionPolled(const Subscription &) = delete; + SubscriptionPolled &operator=(const Subscription &) = delete; + SubscriptionPolled(Subscription &&) = delete; + SubscriptionPolled &operator=(Subscription &&) = delete; /** * Check if there is a new update. diff --git a/src/modules/wind_estimator/wind_estimator_main.cpp b/src/modules/wind_estimator/wind_estimator_main.cpp index 7c0ade08904f..f52698604a3d 100644 --- a/src/modules/wind_estimator/wind_estimator_main.cpp +++ b/src/modules/wind_estimator/wind_estimator_main.cpp @@ -327,7 +327,7 @@ int WindEstimatorModule::print_status() perf_print_counter(_perf_interval); if (_instance > -1) { - uORB::Subscription est{ORB_ID(wind_estimate), (unsigned)_instance}; + uORB::SubscriptionData est{ORB_ID(wind_estimate), (unsigned)_instance}; est.update(); print_message(est.get()); diff --git a/src/systemcmds/tests/test_microbench_uorb.cpp b/src/systemcmds/tests/test_microbench_uorb.cpp index acf86d7d80c1..967787a514a8 100644 --- a/src/systemcmds/tests/test_microbench_uorb.cpp +++ b/src/systemcmds/tests/test_microbench_uorb.cpp @@ -186,21 +186,21 @@ bool MicroBenchORB::time_px4_uorb2() bool updated = false; uint64_t time = 0; - uORB::SubscriptionBase vstatus{ORB_ID(vehicle_status)}; + uORB::Subscription vstatus{ORB_ID(vehicle_status)}; PERF("orb_check vehicle_status", ret = vstatus.updated(), 1000); PERF("orb_stat vehicle_status", time = vstatus.last_update(), 1000); PERF("orb_copy vehicle_status", ret = vstatus.copy(&status), 1000); printf("\n"); - uORB::SubscriptionBase local_pos{ORB_ID(vehicle_local_position)}; + uORB::Subscription local_pos{ORB_ID(vehicle_local_position)}; PERF("orb_check vehicle_local_position", ret = local_pos.updated(), 1000); PERF("orb_stat vehicle_local_position", time = local_pos.last_update(), 1000); PERF("orb_copy vehicle_local_position", ret = local_pos.copy(&lpos), 1000); printf("\n"); - uORB::SubscriptionBase sens_gyro{ORB_ID(sensor_gyro)}; + uORB::Subscription sens_gyro{ORB_ID(sensor_gyro)}; PERF("orb_check sensor_gyro", ret = sens_gyro.updated(), 1000); PERF("orb_stat sensor_gyro", time = sens_gyro.last_update(), 1000); PERF("orb_copy sensor_gyro", ret = sens_gyro.copy(&gyro), 1000);