PX4 Firmware
PX4 Autopilot Software http://px4.io
land_detector::MulticopterLandDetector Class Reference

#include <MulticopterLandDetector.h>

Inheritance diagram for land_detector::MulticopterLandDetector:
Collaboration diagram for land_detector::MulticopterLandDetector:

Public Member Functions

 MulticopterLandDetector ()
 
 ~MulticopterLandDetector () override=default
 
- Public Member Functions inherited from land_detector::LandDetector
 LandDetector ()
 
virtual ~LandDetector ()
 
int print_status () override
 
void start ()
 Get the work queue going. More...
 

Protected Member Functions

void _update_params () override
 Updates parameters. More...
 
void _update_topics () override
 Updates subscribed uORB topics. More...
 
bool _get_landed_state () override
 
bool _get_ground_contact_state () override
 
bool _get_maybe_landed_state () override
 
bool _get_freefall_state () override
 
bool _get_ground_effect_state () override
 
float _get_max_altitude () override
 

Private Member Functions

float _get_takeoff_throttle ()
 Get control mode dependent pilot throttle threshold with which we should quit landed state and take off. More...
 
bool _has_low_thrust ()
 
bool _has_minimal_thrust ()
 
bool _has_altitude_lock ()
 
bool _has_position_lock ()
 
bool _is_climb_rate_enabled ()
 
 DEFINE_PARAMETERS_CUSTOM_PARENT (LandDetector,(ParamFloat< px4::params::LNDMC_ALT_MAX >) _param_lndmc_alt_max,(ParamFloat< px4::params::LNDMC_FFALL_THR >) _param_lndmc_ffall_thr,(ParamFloat< px4::params::LNDMC_FFALL_TTRI >) _param_lndmc_ffall_ttri,(ParamFloat< px4::params::LNDMC_LOW_T_THR >) _param_lndmc_low_t_thr,(ParamFloat< px4::params::LNDMC_ROT_MAX >) _param_lndmc_rot_max,(ParamFloat< px4::params::LNDMC_XY_VEL_MAX >) _param_lndmc_xy_vel_max,(ParamFloat< px4::params::LNDMC_Z_VEL_MAX >) _param_lndmc_z_vel_max)
 

Private Attributes

struct {
   param_t   minThrottle
 
   param_t   hoverThrottle
 
   param_t   minManThrottle
 
   param_t   landSpeed
 
_paramHandle
 Handles for interesting parameters. More...
 
struct {
   float   minThrottle
 
   float   hoverThrottle
 
   float   minManThrottle
 
   float   landSpeed
 
_params
 
uORB::Subscription _actuator_controls_sub {ORB_ID(actuator_controls_0)}
 
uORB::Subscription _battery_sub {ORB_ID(battery_status)}
 
uORB::Subscription _vehicle_acceleration_sub {ORB_ID(vehicle_acceleration)}
 
uORB::Subscription _vehicle_angular_velocity_sub {ORB_ID(vehicle_angular_velocity)}
 
uORB::Subscription _vehicle_control_mode_sub {ORB_ID(vehicle_control_mode)}
 
uORB::Subscription _vehicle_local_position_sub {ORB_ID(vehicle_local_position)}
 
uORB::Subscription _vehicle_local_position_setpoint_sub {ORB_ID(vehicle_local_position_setpoint)}
 
actuator_controls_s _actuator_controls {}
 
battery_status_s _battery_status {}
 
vehicle_angular_velocity_s _vehicle_angular_velocity {}
 
vehicle_control_mode_s _vehicle_control_mode {}
 
vehicle_local_position_setpoint_s _vehicle_local_position_setpoint {}
 
hrt_abstime _min_trust_start {0}
 timestamp when minimum trust was applied first More...
 
hrt_abstime _landed_time {0}
 
bool _in_descend {false}
 vehicle is desending More...
 
bool _horizontal_movement {false}
 vehicle is moving horizontally More...
 

Static Private Attributes

static constexpr hrt_abstime LAND_DETECTOR_TRIGGER_TIME_US = 300_ms
 Time in us that landing conditions have to hold before triggering a land. More...
 
static constexpr hrt_abstime MAYBE_LAND_DETECTOR_TRIGGER_TIME_US = 250_ms
 Time in us that almost landing conditions have to hold before triggering almost landed . More...
 
static constexpr hrt_abstime GROUND_CONTACT_TRIGGER_TIME_US = 350_ms
 Time in us that ground contact condition have to hold before triggering contact ground. More...
 
static constexpr hrt_abstime LAND_DETECTOR_LAND_PHASE_TIME_US = 2_s
 Time interval in us in which wider acceptance thresholds are used after landed. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from land_detector::LandDetector
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 
static int task_spawn (int argc, char *argv[])
 
- Protected Attributes inherited from land_detector::LandDetector
systemlib::Hysteresis _freefall_hysteresis {false}
 
systemlib::Hysteresis _landed_hysteresis {true}
 
systemlib::Hysteresis _maybe_landed_hysteresis {true}
 
systemlib::Hysteresis _ground_contact_hysteresis {true}
 
systemlib::Hysteresis _ground_effect_hysteresis {false}
 
actuator_armed_s _actuator_armed {}
 
vehicle_acceleration_s _vehicle_acceleration {}
 
vehicle_land_detected_s _land_detected
 
vehicle_local_position_s _vehicle_local_position {}
 
uORB::Publication< vehicle_land_detected_s_vehicle_land_detected_pub {ORB_ID(vehicle_land_detected)}
 
- Static Protected Attributes inherited from land_detector::LandDetector
static constexpr uint32_t LAND_DETECTOR_UPDATE_INTERVAL = 20_ms
 Run main land detector loop at this interval. More...
 

Detailed Description

Definition at line 59 of file MulticopterLandDetector.h.

Constructor & Destructor Documentation

◆ MulticopterLandDetector()

land_detector::MulticopterLandDetector::MulticopterLandDetector ( )

◆ ~MulticopterLandDetector()

land_detector::MulticopterLandDetector::~MulticopterLandDetector ( )
overridedefault

Member Function Documentation

◆ _get_freefall_state()

bool land_detector::MulticopterLandDetector::_get_freefall_state ( )
overrideprotectedvirtual
Returns
true if UAV is in free-fall state.

Reimplemented from land_detector::LandDetector.

Definition at line 110 of file MulticopterLandDetector.cpp.

References land_detector::LandDetector::_vehicle_acceleration, vehicle_acceleration_s::timestamp, and vehicle_acceleration_s::xyz.

◆ _get_ground_contact_state()

bool land_detector::MulticopterLandDetector::_get_ground_contact_state ( )
overrideprotectedvirtual

◆ _get_ground_effect_state()

bool land_detector::MulticopterLandDetector::_get_ground_effect_state ( )
overrideprotectedvirtual
Returns
true if vehicle could be in ground effect (close to ground)

Reimplemented from land_detector::LandDetector.

Definition at line 311 of file MulticopterLandDetector.cpp.

References _horizontal_movement, and _in_descend.

◆ _get_landed_state()

bool land_detector::MulticopterLandDetector::_get_landed_state ( )
overrideprotectedvirtual
Returns
true if UAV is in a landed state.

Implements land_detector::LandDetector.

Reimplemented in land_detector::VtolLandDetector.

Definition at line 218 of file MulticopterLandDetector.cpp.

References land_detector::LandDetector::_actuator_armed, _landed_time, land_detector::LandDetector::_maybe_landed_hysteresis, actuator_armed_s::armed, systemlib::Hysteresis::get_state(), and hrt_absolute_time().

Referenced by land_detector::VtolLandDetector::_get_landed_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _get_max_altitude()

float land_detector::MulticopterLandDetector::_get_max_altitude ( )
overrideprotectedvirtual
Returns
maximum altitude that can be reached

Reimplemented from land_detector::LandDetector.

Definition at line 242 of file MulticopterLandDetector.cpp.

References _battery_status, f(), and battery_status_s::warning.

Here is the call graph for this function:

◆ _get_maybe_landed_state()

bool land_detector::MulticopterLandDetector::_get_maybe_landed_state ( )
overrideprotectedvirtual
Returns
true if UAV is in almost landed state

Reimplemented from land_detector::LandDetector.

Reimplemented in land_detector::VtolLandDetector.

Definition at line 172 of file MulticopterLandDetector.cpp.

References land_detector::LandDetector::_actuator_armed, land_detector::LandDetector::_ground_contact_hysteresis, _has_altitude_lock(), _has_minimal_thrust(), _landed_time, _min_trust_start, _vehicle_angular_velocity, actuator_armed_s::armed, systemlib::Hysteresis::get_state(), hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), LAND_DETECTOR_LAND_PHASE_TIME_US, math::radians(), and vehicle_angular_velocity_s::xyz.

Referenced by land_detector::VtolLandDetector::_get_maybe_landed_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _get_takeoff_throttle()

float land_detector::MulticopterLandDetector::_get_takeoff_throttle ( )
private

Get control mode dependent pilot throttle threshold with which we should quit landed state and take off.

◆ _has_altitude_lock()

bool land_detector::MulticopterLandDetector::_has_altitude_lock ( )
private

Definition at line 266 of file MulticopterLandDetector.cpp.

References land_detector::LandDetector::_vehicle_local_position, hrt_elapsed_time(), vehicle_local_position_s::timestamp, and vehicle_local_position_s::z_valid.

Referenced by _get_ground_contact_state(), _get_maybe_landed_state(), and _has_position_lock().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _has_low_thrust()

bool land_detector::MulticopterLandDetector::_has_low_thrust ( )
private

Definition at line 287 of file MulticopterLandDetector.cpp.

References _actuator_controls, _params, and actuator_controls_s::control.

Referenced by _get_ground_contact_state().

Here is the caller graph for this function:

◆ _has_minimal_thrust()

bool land_detector::MulticopterLandDetector::_has_minimal_thrust ( )
private

Definition at line 297 of file MulticopterLandDetector.cpp.

References _actuator_controls, _params, _vehicle_control_mode, actuator_controls_s::control, f(), and vehicle_control_mode_s::flag_control_climb_rate_enabled.

Referenced by _get_maybe_landed_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _has_position_lock()

bool land_detector::MulticopterLandDetector::_has_position_lock ( )
private

Definition at line 273 of file MulticopterLandDetector.cpp.

References _has_altitude_lock(), land_detector::LandDetector::_vehicle_local_position, and vehicle_local_position_s::xy_valid.

Referenced by _get_ground_contact_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _is_climb_rate_enabled()

bool land_detector::MulticopterLandDetector::_is_climb_rate_enabled ( )
private

Definition at line 278 of file MulticopterLandDetector.cpp.

References _vehicle_control_mode, _vehicle_local_position_setpoint, vehicle_control_mode_s::flag_control_climb_rate_enabled, hrt_elapsed_time(), vehicle_local_position_setpoint_s::timestamp, and vehicle_local_position_setpoint_s::vz.

Referenced by _get_ground_contact_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_params()

void land_detector::MulticopterLandDetector::_update_params ( )
overrideprotectedvirtual

Updates parameters.

Reimplemented from land_detector::LandDetector.

Definition at line 98 of file MulticopterLandDetector.cpp.

References land_detector::LandDetector::_freefall_hysteresis, _paramHandle, _params, land_detector::LandDetector::_update_params(), hrt_abstime, param_get(), and systemlib::Hysteresis::set_hysteresis_time_from().

Here is the call graph for this function:

◆ _update_topics()

void land_detector::MulticopterLandDetector::_update_topics ( )
overrideprotectedvirtual

Updates subscribed uORB topics.

Reimplemented from land_detector::LandDetector.

Reimplemented in land_detector::VtolLandDetector.

Definition at line 87 of file MulticopterLandDetector.cpp.

References _actuator_controls, _actuator_controls_sub, _battery_status, _battery_sub, land_detector::LandDetector::_update_topics(), _vehicle_angular_velocity, _vehicle_angular_velocity_sub, _vehicle_control_mode, _vehicle_control_mode_sub, _vehicle_local_position_setpoint, _vehicle_local_position_setpoint_sub, and uORB::Subscription::update().

Referenced by land_detector::VtolLandDetector::_update_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ DEFINE_PARAMETERS_CUSTOM_PARENT()

land_detector::MulticopterLandDetector::DEFINE_PARAMETERS_CUSTOM_PARENT ( LandDetector  ,
(ParamFloat< px4::params::LNDMC_ALT_MAX >)  _param_lndmc_alt_max,
(ParamFloat< px4::params::LNDMC_FFALL_THR >)  _param_lndmc_ffall_thr,
(ParamFloat< px4::params::LNDMC_FFALL_TTRI >)  _param_lndmc_ffall_ttri,
(ParamFloat< px4::params::LNDMC_LOW_T_THR >)  _param_lndmc_low_t_thr,
(ParamFloat< px4::params::LNDMC_ROT_MAX >)  _param_lndmc_rot_max,
(ParamFloat< px4::params::LNDMC_XY_VEL_MAX >)  _param_lndmc_xy_vel_max,
(ParamFloat< px4::params::LNDMC_Z_VEL_MAX >)  _param_lndmc_z_vel_max 
)
private

Member Data Documentation

◆ _actuator_controls

actuator_controls_s land_detector::MulticopterLandDetector::_actuator_controls {}
private

Definition at line 122 of file MulticopterLandDetector.h.

Referenced by _has_low_thrust(), _has_minimal_thrust(), and _update_topics().

◆ _actuator_controls_sub

uORB::Subscription land_detector::MulticopterLandDetector::_actuator_controls_sub {ORB_ID(actuator_controls_0)}
private

Definition at line 114 of file MulticopterLandDetector.h.

Referenced by _update_topics().

◆ _battery_status

battery_status_s land_detector::MulticopterLandDetector::_battery_status {}
private

Definition at line 123 of file MulticopterLandDetector.h.

Referenced by _get_max_altitude(), and _update_topics().

◆ _battery_sub

uORB::Subscription land_detector::MulticopterLandDetector::_battery_sub {ORB_ID(battery_status)}
private

Definition at line 115 of file MulticopterLandDetector.h.

Referenced by _update_topics().

◆ _horizontal_movement

bool land_detector::MulticopterLandDetector::_horizontal_movement {false}
private

vehicle is moving horizontally

Definition at line 132 of file MulticopterLandDetector.h.

Referenced by _get_ground_contact_state(), and _get_ground_effect_state().

◆ _in_descend

bool land_detector::MulticopterLandDetector::_in_descend {false}
private

vehicle is desending

Definition at line 131 of file MulticopterLandDetector.h.

Referenced by _get_ground_contact_state(), and _get_ground_effect_state().

◆ _landed_time

hrt_abstime land_detector::MulticopterLandDetector::_landed_time {0}
private

◆ _min_trust_start

hrt_abstime land_detector::MulticopterLandDetector::_min_trust_start {0}
private

timestamp when minimum trust was applied first

Definition at line 128 of file MulticopterLandDetector.h.

Referenced by _get_maybe_landed_state().

◆ _paramHandle

struct { ... } land_detector::MulticopterLandDetector::_paramHandle

Handles for interesting parameters.

Referenced by _update_params(), and MulticopterLandDetector().

◆ _params

struct { ... } land_detector::MulticopterLandDetector::_params

◆ _vehicle_acceleration_sub

uORB::Subscription land_detector::MulticopterLandDetector::_vehicle_acceleration_sub {ORB_ID(vehicle_acceleration)}
private

Definition at line 116 of file MulticopterLandDetector.h.

◆ _vehicle_angular_velocity

vehicle_angular_velocity_s land_detector::MulticopterLandDetector::_vehicle_angular_velocity {}
private

Definition at line 124 of file MulticopterLandDetector.h.

Referenced by _get_maybe_landed_state(), and _update_topics().

◆ _vehicle_angular_velocity_sub

uORB::Subscription land_detector::MulticopterLandDetector::_vehicle_angular_velocity_sub {ORB_ID(vehicle_angular_velocity)}
private

Definition at line 117 of file MulticopterLandDetector.h.

Referenced by _update_topics().

◆ _vehicle_control_mode

vehicle_control_mode_s land_detector::MulticopterLandDetector::_vehicle_control_mode {}
private

◆ _vehicle_control_mode_sub

uORB::Subscription land_detector::MulticopterLandDetector::_vehicle_control_mode_sub {ORB_ID(vehicle_control_mode)}
private

Definition at line 118 of file MulticopterLandDetector.h.

Referenced by _update_topics().

◆ _vehicle_local_position_setpoint

vehicle_local_position_setpoint_s land_detector::MulticopterLandDetector::_vehicle_local_position_setpoint {}
private

◆ _vehicle_local_position_setpoint_sub

uORB::Subscription land_detector::MulticopterLandDetector::_vehicle_local_position_setpoint_sub {ORB_ID(vehicle_local_position_setpoint)}
private

Definition at line 120 of file MulticopterLandDetector.h.

Referenced by _update_topics().

◆ _vehicle_local_position_sub

uORB::Subscription land_detector::MulticopterLandDetector::_vehicle_local_position_sub {ORB_ID(vehicle_local_position)}
private

Definition at line 119 of file MulticopterLandDetector.h.

◆ GROUND_CONTACT_TRIGGER_TIME_US

constexpr hrt_abstime land_detector::MulticopterLandDetector::GROUND_CONTACT_TRIGGER_TIME_US = 350_ms
staticprivate

Time in us that ground contact condition have to hold before triggering contact ground.

Definition at line 94 of file MulticopterLandDetector.h.

Referenced by MulticopterLandDetector().

◆ hoverThrottle [1/2]

param_t land_detector::MulticopterLandDetector::hoverThrottle

Definition at line 102 of file MulticopterLandDetector.h.

◆ hoverThrottle [2/2]

float land_detector::MulticopterLandDetector::hoverThrottle

Definition at line 109 of file MulticopterLandDetector.h.

◆ LAND_DETECTOR_LAND_PHASE_TIME_US

constexpr hrt_abstime land_detector::MulticopterLandDetector::LAND_DETECTOR_LAND_PHASE_TIME_US = 2_s
staticprivate

Time interval in us in which wider acceptance thresholds are used after landed.

Definition at line 97 of file MulticopterLandDetector.h.

Referenced by _get_ground_contact_state(), and _get_maybe_landed_state().

◆ LAND_DETECTOR_TRIGGER_TIME_US

constexpr hrt_abstime land_detector::MulticopterLandDetector::LAND_DETECTOR_TRIGGER_TIME_US = 300_ms
staticprivate

Time in us that landing conditions have to hold before triggering a land.

Definition at line 88 of file MulticopterLandDetector.h.

Referenced by MulticopterLandDetector().

◆ landSpeed [1/2]

param_t land_detector::MulticopterLandDetector::landSpeed

Definition at line 104 of file MulticopterLandDetector.h.

◆ landSpeed [2/2]

float land_detector::MulticopterLandDetector::landSpeed

Definition at line 111 of file MulticopterLandDetector.h.

◆ MAYBE_LAND_DETECTOR_TRIGGER_TIME_US

constexpr hrt_abstime land_detector::MulticopterLandDetector::MAYBE_LAND_DETECTOR_TRIGGER_TIME_US = 250_ms
staticprivate

Time in us that almost landing conditions have to hold before triggering almost landed .

Definition at line 91 of file MulticopterLandDetector.h.

Referenced by MulticopterLandDetector().

◆ minManThrottle [1/2]

param_t land_detector::MulticopterLandDetector::minManThrottle

Definition at line 103 of file MulticopterLandDetector.h.

◆ minManThrottle [2/2]

float land_detector::MulticopterLandDetector::minManThrottle

Definition at line 110 of file MulticopterLandDetector.h.

◆ minThrottle [1/2]

param_t land_detector::MulticopterLandDetector::minThrottle

Definition at line 101 of file MulticopterLandDetector.h.

◆ minThrottle [2/2]

float land_detector::MulticopterLandDetector::minThrottle

Definition at line 108 of file MulticopterLandDetector.h.


The documentation for this class was generated from the following files: