Skip to content

Commit

Permalink
uORB::Subscription shift SubscriptionBase naming to encourage usage
Browse files Browse the repository at this point in the history
 - uORB::SubscriptionBase -> uORB::Subscription
 - uORB::Subscription -> uORB::SubscriptionData
  • Loading branch information
dagar committed Apr 8, 2019
1 parent 5387e4a commit a7528d8
Show file tree
Hide file tree
Showing 31 changed files with 111 additions and 111 deletions.
2 changes: 1 addition & 1 deletion src/drivers/md25/md25.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,7 +270,7 @@ class MD25 : public device::I2C
struct pollfd _controlPoll;

/** actuator controls subscription */
uORB::Subscription<actuator_controls_s> _actuators;
uORB::SubscriptionData<actuator_controls_s> _actuators;

// local copy of data from i2c device
uint8_t _version;
Expand Down
14 changes: 7 additions & 7 deletions src/examples/segway/blocks.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,13 +94,13 @@ class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
// subscriptions
uORB::SubscriptionPolled<vehicle_attitude_s> _att;

uORB::Subscription<manual_control_setpoint_s> _manual;
uORB::Subscription<parameter_update_s> _param_update;
uORB::Subscription<position_setpoint_triplet_s> _missionCmd;
uORB::Subscription<vehicle_attitude_setpoint_s> _attCmd;
uORB::Subscription<vehicle_global_position_s> _pos;
uORB::Subscription<vehicle_rates_setpoint_s> _ratesCmd;
uORB::Subscription<vehicle_status_s> _status;
uORB::SubscriptionData<manual_control_setpoint_s> _manual;
uORB::SubscriptionData<parameter_update_s> _param_update;
uORB::SubscriptionData<position_setpoint_triplet_s> _missionCmd;
uORB::SubscriptionData<vehicle_attitude_setpoint_s> _attCmd;
uORB::SubscriptionData<vehicle_global_position_s> _pos;
uORB::SubscriptionData<vehicle_rates_setpoint_s> _ratesCmd;
uORB::SubscriptionData<vehicle_status_s> _status;

// publications
uORB::Publication<actuator_controls_s> _actuators;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/CollisionPrevention/CollisionPrevention.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<obstacle_distance_s> *_sub_obstacle_distance{nullptr}; /**< obstacle distances received form a range sensor */
uORB::SubscriptionData<obstacle_distance_s> *_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;
Expand Down
6 changes: 3 additions & 3 deletions src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<home_position_s> *_sub_home_position{nullptr};
uORB::SubscriptionData<home_position_s> *_sub_home_position{nullptr};

State _current_state{State::none};
float _target_acceptance_radius = 0.0f; /**< Acceptances radius of the target */
Expand All @@ -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<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};
uORB::Subscription<vehicle_status_s> *_sub_vehicle_status{nullptr};
uORB::SubscriptionData<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};
uORB::SubscriptionData<vehicle_status_s> *_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. */
Expand Down
4 changes: 2 additions & 2 deletions src/lib/FlightTasks/tasks/FlightTask/FlightTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,8 +173,8 @@ class FlightTask : public ModuleParams

protected:

uORB::Subscription<vehicle_local_position_s> *_sub_vehicle_local_position{nullptr};
uORB::Subscription<vehicle_attitude_s> *_sub_attitude{nullptr};
uORB::SubscriptionData<vehicle_local_position_s> *_sub_vehicle_local_position{nullptr};
uORB::SubscriptionData<vehicle_attitude_s> *_sub_attitude{nullptr};
uint8_t _heading_reset_counter{0}; /**< estimator heading reset */

/**
Expand Down
9 changes: 5 additions & 4 deletions src/lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class SubscriptionArray
* @return true on success, false otherwise (subscription set to nullptr)
*/
template<class T>
bool get(const struct orb_metadata *meta, uORB::Subscription<T> *&subscription, unsigned instance = 0);
bool get(const struct orb_metadata *meta, uORB::SubscriptionData<T> *&subscription, unsigned instance = 0);

/**
* update all subscriptions (if new data is available)
Expand All @@ -81,13 +81,14 @@ class SubscriptionArray


template<class T>
bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::Subscription<T> *&subscription, unsigned instance)
bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::SubscriptionData<T> *&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<uORB::Subscription<T>*>(_subscriptions[i]);
subscription = reinterpret_cast<uORB::SubscriptionData<T>*>(_subscriptions[i]);
return true;
}
}
Expand All @@ -100,7 +101,7 @@ bool SubscriptionArray::get(const struct orb_metadata *meta, uORB::Subscription<
}
}

subscription = new uORB::Subscription<T>(meta, 0, instance);
subscription = new uORB::SubscriptionData<T>(meta, 0, instance);

if (!subscription) {
return false;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/FlightTasks/tasks/Manual/FlightTaskManual.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<manual_control_setpoint_s> *_sub_manual_control_setpoint{nullptr};
uORB::SubscriptionData<manual_control_setpoint_s> *_sub_manual_control_setpoint{nullptr};

DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask,
(ParamFloat<px4::params::MPC_HOLD_DZ>) _param_mpc_hold_dz, /**< 0-deadzone around the center for the sticks */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class FlightTaskManualAltitude : public FlightTaskManual
*/
void _respectGroundSlowdown();

uORB::Subscription<home_position_s> *_sub_home_position{nullptr};
uORB::SubscriptionData<home_position_s> *_sub_home_position{nullptr};

uint8_t _reset_counter = 0; /**< counter for estimator resets in z-direction */
float _max_speed_up = 10.0f;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/FlightTasks/tasks/Offboard/FlightTaskOffboard.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class FlightTaskOffboard : public FlightTask
bool updateInitialize() override;

protected:
uORB::Subscription<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};
uORB::SubscriptionData<position_setpoint_triplet_s> *_sub_triplet_setpoint{nullptr};
private:
matrix::Vector3f _position_lock{};

Expand Down
4 changes: 2 additions & 2 deletions src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ class ObstacleAvoidance : public ModuleParams

private:

uORB::Subscription<vehicle_trajectory_waypoint_s> *_sub_vehicle_trajectory_waypoint{nullptr}; /**< vehicle trajectory waypoint subscription */
uORB::Subscription<vehicle_status_s> *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */
uORB::SubscriptionData<vehicle_trajectory_waypoint_s> *_sub_vehicle_trajectory_waypoint{nullptr}; /**< vehicle trajectory waypoint subscription */
uORB::SubscriptionData<vehicle_status_s> *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */

DEFINE_PARAMETERS(
(ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID, /**< obstacle avoidance enabled */
Expand Down
13 changes: 6 additions & 7 deletions src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/telemetry_status.h>
using math::constrain;
using uORB::Publication;
using uORB::Subscription;

using namespace time_literals;

Expand Down Expand Up @@ -206,12 +204,13 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
bool _print_avoidance_msg_once{false};

// Subscriptions
Subscription<estimator_status_s> _estimator_status_sub{ORB_ID(estimator_status)};
Subscription<mission_result_s> _mission_result_sub{ORB_ID(mission_result)};
Subscription<vehicle_global_position_s> _global_position_sub{ORB_ID(vehicle_global_position)};
Subscription<vehicle_local_position_s> _local_position_sub{ORB_ID(vehicle_local_position)};
uORB::SubscriptionData<estimator_status_s> _estimator_status_sub{ORB_ID(estimator_status)};
uORB::SubscriptionData<mission_result_s> _mission_result_sub{ORB_ID(mission_result)};
uORB::SubscriptionData<vehicle_global_position_s> _global_position_sub{ORB_ID(vehicle_global_position)};
uORB::SubscriptionData<vehicle_local_position_s> _local_position_sub{ORB_ID(vehicle_local_position)};

Publication<home_position_s> _home_pub{ORB_ID(home_position)};
// Publications
uORB::Publication<home_position_s> _home_pub{ORB_ID(home_position)};

orb_advert_t _status_pub{nullptr};
};
Expand Down
8 changes: 4 additions & 4 deletions src/modules/commander/PreflightCheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ static bool magnometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &sta

if (exists) {

uORB::Subscription<sensor_mag_s> magnetometer{ORB_ID(sensor_mag), 0, instance};
uORB::SubscriptionData<sensor_mag_s> magnetometer{ORB_ID(sensor_mag), 0, instance};

mag_valid = (hrt_elapsed_time(&magnetometer.get().timestamp) < 1_s);

Expand Down Expand Up @@ -245,7 +245,7 @@ static bool accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &

if (exists) {

uORB::Subscription<sensor_accel_s> accel{ORB_ID(sensor_accel), 0, instance};
uORB::SubscriptionData<sensor_accel_s> accel{ORB_ID(sensor_accel), 0, instance};

accel_valid = (hrt_elapsed_time(&accel.get().timestamp) < 1_s);

Expand Down Expand Up @@ -309,7 +309,7 @@ static bool gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, u

if (exists) {

uORB::Subscription<sensor_gyro_s> gyro{ORB_ID(sensor_gyro), 0, instance};
uORB::SubscriptionData<sensor_gyro_s> gyro{ORB_ID(sensor_gyro), 0, instance};

gyro_valid = (hrt_elapsed_time(&gyro.get().timestamp) < 1_s);

Expand Down Expand Up @@ -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<sensor_baro_s> baro{ORB_ID(sensor_baro), 0, instance};
uORB::SubscriptionData<sensor_baro_s> baro{ORB_ID(sensor_baro), 0, instance};

baro_valid = (hrt_elapsed_time(&baro.get().timestamp) < 1_s);

Expand Down
6 changes: 3 additions & 3 deletions src/modules/commander/failure_detector/FailureDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -79,8 +79,8 @@ class FailureDetector : public ModuleParams
)

// Subscriptions
Subscription<vehicle_attitude_s> _sub_vehicle_attitude_setpoint;
Subscription<vehicle_attitude_s> _sub_vehicule_attitude;
SubscriptionData<vehicle_attitude_s> _sub_vehicle_attitude_setpoint;
SubscriptionData<vehicle_attitude_s> _sub_vehicule_attitude;

uint8_t _status{FAILURE_NONE};

Expand Down
4 changes: 2 additions & 2 deletions src/modules/fw_att_control/FixedwingAttitudeControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@
using matrix::Eulerf;
using matrix::Quatf;

using uORB::Subscription;
using uORB::SubscriptionData;

class FixedwingAttitudeControl final : public ModuleBase<FixedwingAttitudeControl>
{
Expand Down Expand Up @@ -123,7 +123,7 @@ class FixedwingAttitudeControl final : public ModuleBase<FixedwingAttitudeContro
vehicle_rates_setpoint_s _rates_sp {}; /* attitude rates setpoint */
vehicle_status_s _vehicle_status {}; /**< vehicle status */

Subscription<airspeed_s> _airspeed_sub;
SubscriptionData<airspeed_s> _airspeed_sub;

perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
Expand Down
6 changes: 3 additions & 3 deletions src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -181,8 +181,8 @@ class FixedwingPositionControl final : public ModuleBase<FixedwingPositionContro
vehicle_land_detected_s _vehicle_land_detected {}; ///< vehicle land detected */
vehicle_status_s _vehicle_status {}; ///< vehicle status */

Subscription<airspeed_s> _sub_airspeed;
Subscription<sensor_bias_s> _sub_sensors;
SubscriptionData<airspeed_s> _sub_airspeed;
SubscriptionData<sensor_bias_s> _sub_sensors;

perf_counter_t _loop_perf; ///< loop performance counter */

Expand Down
6 changes: 3 additions & 3 deletions src/modules/gnd_pos_control/GroundRoverPositionControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@

using matrix::Dcmf;

using uORB::Subscription;
using uORB::SubscriptionData;

class GroundRoverPositionControl
{
Expand Down Expand Up @@ -110,8 +110,8 @@ class GroundRoverPositionControl
vehicle_control_mode_s _control_mode{}; /**< control mode */
vehicle_global_position_s _global_pos{}; /**< global vehicle position */

Subscription<vehicle_attitude_s> _sub_attitude;
Subscription<sensor_bias_s> _sub_sensors;
SubscriptionData<vehicle_attitude_s> _sub_attitude;
SubscriptionData<sensor_bias_s> _sub_sensors;

perf_counter_t _loop_perf; /**< loop performance counter */

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<distance_sensor_s> *s = _dist_subs[i];
uORB::SubscriptionData<distance_sensor_s> *s = _dist_subs[i];

if (s == _sub_lidar || s == _sub_sonar) { continue; }

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,21 +250,21 @@ class BlockLocalPositionEstimator : public control::SuperBlock, public ModulePar
uORB::SubscriptionPolled<parameter_update_s> _sub_param_update;
uORB::SubscriptionPolled<sensor_combined_s> _sub_sensor;

uORB::Subscription<actuator_armed_s> _sub_armed;
uORB::Subscription<vehicle_land_detected_s> _sub_land;
uORB::Subscription<vehicle_attitude_s> _sub_att;
uORB::Subscription<vehicle_gps_position_s> _sub_gps;
uORB::Subscription<vehicle_odometry_s> _sub_visual_odom;
uORB::Subscription<vehicle_odometry_s> _sub_mocap_odom;
uORB::Subscription<distance_sensor_s> _sub_dist0;
uORB::Subscription<distance_sensor_s> _sub_dist1;
uORB::Subscription<distance_sensor_s> _sub_dist2;
uORB::Subscription<distance_sensor_s> _sub_dist3;
uORB::Subscription<distance_sensor_s> *_dist_subs[N_DIST_SUBS];
uORB::Subscription<distance_sensor_s> *_sub_lidar;
uORB::Subscription<distance_sensor_s> *_sub_sonar;
uORB::Subscription<landing_target_pose_s> _sub_landing_target_pose;
uORB::Subscription<vehicle_air_data_s> _sub_airdata;
uORB::SubscriptionData<actuator_armed_s> _sub_armed;
uORB::SubscriptionData<vehicle_land_detected_s> _sub_land;
uORB::SubscriptionData<vehicle_attitude_s> _sub_att;
uORB::SubscriptionData<vehicle_gps_position_s> _sub_gps;
uORB::SubscriptionData<vehicle_odometry_s> _sub_visual_odom;
uORB::SubscriptionData<vehicle_odometry_s> _sub_mocap_odom;
uORB::SubscriptionData<distance_sensor_s> _sub_dist0;
uORB::SubscriptionData<distance_sensor_s> _sub_dist1;
uORB::SubscriptionData<distance_sensor_s> _sub_dist2;
uORB::SubscriptionData<distance_sensor_s> _sub_dist3;
uORB::SubscriptionData<distance_sensor_s> *_dist_subs[N_DIST_SUBS];
uORB::SubscriptionData<distance_sensor_s> *_sub_lidar;
uORB::SubscriptionData<distance_sensor_s> *_sub_sonar;
uORB::SubscriptionData<landing_target_pose_s> _sub_landing_target_pose;
uORB::SubscriptionData<vehicle_air_data_s> _sub_airdata;

// publications
uORB::Publication<vehicle_local_position_s> _pub_lpos;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/logger/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -868,7 +868,7 @@ void Logger::run()
}

int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
uORB::Subscription<parameter_update_s> parameter_update_sub(ORB_ID(parameter_update));
uORB::SubscriptionData<parameter_update_s> parameter_update_sub(ORB_ID(parameter_update));
int log_message_sub = orb_subscribe(ORB_ID(log_message));
orb_set_interval(log_message_sub, 20);

Expand Down
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<actuator_armed_s> armed_sub{ORB_ID(actuator_armed)};
uORB::SubscriptionData<actuator_armed_s> armed_sub{ORB_ID(actuator_armed)};

/* get the system arming state and abort on arming */
while (_uart_fd < 0) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_mission.h
Original file line number Diff line number Diff line change
Expand Up @@ -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};

Expand Down
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_orb_subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class MavlinkOrbSubscription : public ListNode<MavlinkOrbSubscription *>

private:

uORB::SubscriptionBase _sub;
uORB::Subscription _sub;
};


Expand Down
6 changes: 3 additions & 3 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -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};

Expand Down
2 changes: 1 addition & 1 deletion src/modules/navigator/geofence.h
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class Geofence : public ModuleParams
(ParamFloat<px4::params::GF_MAX_VER_DIST>) _param_gf_max_ver_dist
)

uORB::Subscription<vehicle_air_data_s> _sub_airdata;
uORB::SubscriptionData<vehicle_air_data_s> _sub_airdata;

int _outside_counter{0};
uint16_t _update_counter{0}; ///< dataman update counter: if it does not match, we polygon data was updated
Expand Down
2 changes: 1 addition & 1 deletion src/modules/navigator/mission_feasibility_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -450,7 +450,7 @@ MissionFeasibilityChecker::checkFixedWingLanding(const mission_s &mission, bool

if (MissionBlock::item_contains_position(missionitem_previous)) {

uORB::Subscription<position_controller_landing_status_s> landing_status{ORB_ID(position_controller_landing_status)};
uORB::SubscriptionData<position_controller_landing_status_s> landing_status{ORB_ID(position_controller_landing_status)};
landing_status.forcedUpdate();

const bool landing_status_valid = (landing_status.get().timestamp > 0);
Expand Down
Loading

0 comments on commit a7528d8

Please sign in to comment.