PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <MulticopterLandDetector.h>
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) | |
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... | |
Definition at line 59 of file MulticopterLandDetector.h.
land_detector::MulticopterLandDetector::MulticopterLandDetector | ( | ) |
Definition at line 74 of file MulticopterLandDetector.cpp.
References land_detector::LandDetector::_ground_contact_hysteresis, land_detector::LandDetector::_landed_hysteresis, land_detector::LandDetector::_maybe_landed_hysteresis, _paramHandle, GROUND_CONTACT_TRIGGER_TIME_US, LAND_DETECTOR_TRIGGER_TIME_US, MAYBE_LAND_DETECTOR_TRIGGER_TIME_US, param_find(), and systemlib::Hysteresis::set_hysteresis_time_from().
|
overridedefault |
|
overrideprotectedvirtual |
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.
|
overrideprotectedvirtual |
Reimplemented from land_detector::LandDetector.
Definition at line 128 of file MulticopterLandDetector.cpp.
References land_detector::LandDetector::_actuator_armed, _has_altitude_lock(), _has_low_thrust(), _has_position_lock(), _horizontal_movement, _in_descend, _is_climb_rate_enabled(), _landed_time, _params, land_detector::LandDetector::_vehicle_local_position, _vehicle_local_position_setpoint, actuator_armed_s::armed, f(), hrt_elapsed_time(), LAND_DETECTOR_LAND_PHASE_TIME_US, math::max(), vehicle_local_position_s::vx, vehicle_local_position_s::vy, vehicle_local_position_setpoint_s::vz, and vehicle_local_position_s::vz.
|
overrideprotectedvirtual |
Reimplemented from land_detector::LandDetector.
Definition at line 311 of file MulticopterLandDetector.cpp.
References _horizontal_movement, and _in_descend.
|
overrideprotectedvirtual |
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().
|
overrideprotectedvirtual |
Reimplemented from land_detector::LandDetector.
Definition at line 242 of file MulticopterLandDetector.cpp.
References _battery_status, f(), and battery_status_s::warning.
|
overrideprotectedvirtual |
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().
|
private |
Get control mode dependent pilot throttle threshold with which we should quit landed state and take off.
|
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().
|
private |
Definition at line 287 of file MulticopterLandDetector.cpp.
References _actuator_controls, _params, and actuator_controls_s::control.
Referenced by _get_ground_contact_state().
|
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().
|
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().
|
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().
|
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().
|
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().
|
private |
|
private |
Definition at line 122 of file MulticopterLandDetector.h.
Referenced by _has_low_thrust(), _has_minimal_thrust(), and _update_topics().
|
private |
Definition at line 114 of file MulticopterLandDetector.h.
Referenced by _update_topics().
|
private |
Definition at line 123 of file MulticopterLandDetector.h.
Referenced by _get_max_altitude(), and _update_topics().
|
private |
Definition at line 115 of file MulticopterLandDetector.h.
Referenced by _update_topics().
|
private |
vehicle is moving horizontally
Definition at line 132 of file MulticopterLandDetector.h.
Referenced by _get_ground_contact_state(), and _get_ground_effect_state().
|
private |
vehicle is desending
Definition at line 131 of file MulticopterLandDetector.h.
Referenced by _get_ground_contact_state(), and _get_ground_effect_state().
|
private |
Definition at line 129 of file MulticopterLandDetector.h.
Referenced by _get_ground_contact_state(), _get_landed_state(), and _get_maybe_landed_state().
|
private |
timestamp when minimum trust was applied first
Definition at line 128 of file MulticopterLandDetector.h.
Referenced by _get_maybe_landed_state().
struct { ... } land_detector::MulticopterLandDetector::_paramHandle |
Handles for interesting parameters.
Referenced by _update_params(), and MulticopterLandDetector().
struct { ... } land_detector::MulticopterLandDetector::_params |
Referenced by _get_ground_contact_state(), _has_low_thrust(), _has_minimal_thrust(), and _update_params().
|
private |
Definition at line 116 of file MulticopterLandDetector.h.
|
private |
Definition at line 124 of file MulticopterLandDetector.h.
Referenced by _get_maybe_landed_state(), and _update_topics().
|
private |
Definition at line 117 of file MulticopterLandDetector.h.
Referenced by _update_topics().
|
private |
Definition at line 125 of file MulticopterLandDetector.h.
Referenced by _has_minimal_thrust(), _is_climb_rate_enabled(), and _update_topics().
|
private |
Definition at line 118 of file MulticopterLandDetector.h.
Referenced by _update_topics().
|
private |
Definition at line 126 of file MulticopterLandDetector.h.
Referenced by _get_ground_contact_state(), _is_climb_rate_enabled(), and _update_topics().
|
private |
Definition at line 120 of file MulticopterLandDetector.h.
Referenced by _update_topics().
|
private |
Definition at line 119 of file MulticopterLandDetector.h.
|
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().
param_t land_detector::MulticopterLandDetector::hoverThrottle |
Definition at line 102 of file MulticopterLandDetector.h.
float land_detector::MulticopterLandDetector::hoverThrottle |
Definition at line 109 of file MulticopterLandDetector.h.
|
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().
|
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().
param_t land_detector::MulticopterLandDetector::landSpeed |
Definition at line 104 of file MulticopterLandDetector.h.
float land_detector::MulticopterLandDetector::landSpeed |
Definition at line 111 of file MulticopterLandDetector.h.
|
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().
param_t land_detector::MulticopterLandDetector::minManThrottle |
Definition at line 103 of file MulticopterLandDetector.h.
float land_detector::MulticopterLandDetector::minManThrottle |
Definition at line 110 of file MulticopterLandDetector.h.
param_t land_detector::MulticopterLandDetector::minThrottle |
Definition at line 101 of file MulticopterLandDetector.h.
float land_detector::MulticopterLandDetector::minThrottle |
Definition at line 108 of file MulticopterLandDetector.h.