PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <precland.h>
Classes | |
struct | _map_ref |
reference for local/global projections More... | |
Public Member Functions | |
PrecLand (Navigator *navigator) | |
~PrecLand () override=default | |
void | on_activation () override |
This function is called one time when mode becomes active, pos_sp_triplet must be initialized here. More... | |
void | on_active () override |
This function is called while the mode is active. More... | |
void | set_mode (PrecLandMode mode) |
PrecLandMode | get_mode () |
Public Member Functions inherited from MissionBlock | |
MissionBlock (Navigator *navigator) | |
Constructor. More... | |
virtual | ~MissionBlock ()=default |
MissionBlock (const MissionBlock &)=delete | |
MissionBlock & | operator= (const MissionBlock &)=delete |
Public Member Functions inherited from NavigatorMode | |
NavigatorMode (Navigator *navigator) | |
virtual | ~NavigatorMode ()=default |
NavigatorMode (const NavigatorMode &)=delete | |
NavigatorMode | operator= (const NavigatorMode &)=delete |
void | run (bool active) |
virtual void | on_inactive () |
This function is called while the mode is inactive. More... | |
virtual void | on_inactivation () |
This function is called one time when mode becomes inactive. More... | |
Private Member Functions | |
void | updateParams () override |
void | run_state_start () |
void | run_state_horizontal_approach () |
void | run_state_descend_above_target () |
void | run_state_final_approach () |
void | run_state_search () |
void | run_state_fallback () |
bool | switch_to_state_start () |
bool | switch_to_state_horizontal_approach () |
bool | switch_to_state_descend_above_target () |
bool | switch_to_state_final_approach () |
bool | switch_to_state_search () |
bool | switch_to_state_fallback () |
bool | switch_to_state_done () |
bool | check_state_conditions (PrecLandState state) |
void | slewrate (float &sp_x, float &sp_y) |
DEFINE_PARAMETERS ((ParamFloat< px4::params::PLD_BTOUT >) _param_pld_btout,(ParamFloat< px4::params::PLD_HACC_RAD >) _param_pld_hacc_rad,(ParamFloat< px4::params::PLD_FAPPR_ALT >) _param_pld_fappr_alt,(ParamFloat< px4::params::PLD_SRCH_ALT >) _param_pld_srch_alt,(ParamFloat< px4::params::PLD_SRCH_TOUT >) _param_pld_srch_tout,(ParamInt< px4::params::PLD_MAX_SRCH >) _param_pld_max_srch) param_t _handle_param_acceleration_hor | |
Private Attributes | |
landing_target_pose_s | _target_pose {} |
precision landing target position More... | |
uORB::Subscription | _target_pose_sub {ORB_ID(landing_target_pose)} |
bool | _target_pose_valid {false} |
whether we have received a landing target position message More... | |
bool | _target_pose_updated {false} |
wether the landing target position message is updated More... | |
uint64_t | _state_start_time {0} |
time when we entered current state More... | |
uint64_t | _last_slewrate_time {0} |
time when we last limited setpoint changes More... | |
uint64_t | _target_acquired_time {0} |
time when we first saw the landing target during search More... | |
uint64_t | _point_reached_time {0} |
time when we reached a setpoint More... | |
int | _search_cnt {0} |
counter of how many times we had to search for the landing target More... | |
float | _approach_alt {0.0f} |
altitude at which to stay during horizontal approach More... | |
matrix::Vector2f | _sp_pev |
matrix::Vector2f | _sp_pev_prev |
PrecLandState | _state {PrecLandState::Start} |
PrecLandMode | _mode {PrecLandMode::Opportunistic} |
param_t | _handle_param_xy_vel_cruise {PARAM_INVALID} |
float | _param_acceleration_hor {0.0f} |
float | _param_xy_vel_cruise {0.0f} |
Additional Inherited Members | |
Static Public Member Functions inherited from MissionBlock | |
static bool | item_contains_position (const mission_item_s &item) |
Protected Member Functions inherited from MissionBlock | |
bool | is_mission_item_reached () |
Check if mission item has been reached. More... | |
void | reset_mission_item_reached () |
Reset all reached flags. More... | |
bool | mission_item_to_position_setpoint (const mission_item_s &item, position_setpoint_s *sp) |
Convert a mission item to a position setpoint. More... | |
void | set_loiter_item (struct mission_item_s *item, float min_clearance=-1.0f) |
Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position. More... | |
void | set_takeoff_item (struct mission_item_s *item, float abs_altitude, float min_pitch=0.0f) |
Set a takeoff mission item. More... | |
void | set_land_item (struct mission_item_s *item, bool at_current_location) |
Set a land mission item. More... | |
void | set_idle_item (struct mission_item_s *item) |
Set idle mission item. More... | |
void | set_vtol_transition_item (struct mission_item_s *item, const uint8_t new_mode) |
Set vtol transition item. More... | |
void | mission_apply_limitation (mission_item_s &item) |
General function used to adjust the mission item based on vehicle specific limitations. More... | |
void | issue_command (const mission_item_s &item) |
float | get_time_inside (const mission_item_s &item) const |
float | get_absolute_altitude_for_item (const mission_item_s &mission_item) const |
Protected Attributes inherited from MissionBlock | |
mission_item_s | _mission_item {} |
bool | _waypoint_position_reached {false} |
bool | _waypoint_yaw_reached {false} |
bool | _waypoint_position_reached_previously {false} |
hrt_abstime | _time_first_inside_orbit {0} |
hrt_abstime | _action_start {0} |
hrt_abstime | _time_wp_reached {0} |
uORB::Publication< actuator_controls_s > | _actuator_pub {ORB_ID(actuator_controls_2)} |
Protected Attributes inherited from NavigatorMode | |
Navigator * | _navigator {nullptr} |
Definition at line 67 of file precland.h.
PrecLand::PrecLand | ( | Navigator * | navigator | ) |
Definition at line 62 of file precland.cpp.
References _handle_param_xy_vel_cruise, param_find(), and updateParams().
|
overridedefault |
|
private |
Definition at line 467 of file precland.cpp.
References NavigatorMode::_navigator, _search_cnt, _state, _target_pose, _target_pose_updated, _target_pose_valid, landing_target_pose_s::abs_pos_valid, DescendAboveTarget, Fallback, FinalApproach, Navigator::get_local_position(), HorizontalApproach, hrt_absolute_time(), Search, Start, landing_target_pose_s::timestamp, vehicle_local_position_s::x, landing_target_pose_s::x_abs, vehicle_local_position_s::y, landing_target_pose_s::y_abs, vehicle_local_position_s::z, and landing_target_pose_s::z_abs.
Referenced by run_state_descend_above_target(), run_state_horizontal_approach(), run_state_search(), switch_to_state_descend_above_target(), switch_to_state_final_approach(), switch_to_state_horizontal_approach(), and switch_to_state_start().
|
inlineprivate |
Definition at line 128 of file precland.h.
References PARAM_INVALID.
|
inline |
Definition at line 78 of file precland.h.
|
overridevirtual |
This function is called one time when mode becomes active, pos_sp_triplet must be initialized here.
Reimplemented from NavigatorMode.
Definition at line 73 of file precland.cpp.
References _last_slewrate_time, NavigatorMode::_navigator, _search_cnt, _sp_pev, _sp_pev_prev, _state, vehicle_global_position_s::alt, position_setpoint_s::alt, position_setpoint_triplet_s::current, Navigator::get_global_position(), Navigator::get_local_position(), Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, map_projection_init(), map_projection_initialized(), position_setpoint_triplet_s::next, vehicle_local_position_s::ref_lat, vehicle_local_position_s::ref_lon, Start, switch_to_state_start(), position_setpoint_s::timestamp, and position_setpoint_s::valid.
Referenced by Mission::set_mission_items().
|
overridevirtual |
This function is called while the mode is active.
Reimplemented from NavigatorMode.
Definition at line 107 of file precland.cpp.
References NavigatorMode::_navigator, _state, _target_pose, _target_pose_sub, _target_pose_updated, _target_pose_valid, DescendAboveTarget, Done, Fallback, FinalApproach, Navigator::get_land_detected(), HorizontalApproach, hrt_elapsed_time(), vehicle_land_detected_s::landed, run_state_descend_above_target(), run_state_fallback(), run_state_final_approach(), run_state_horizontal_approach(), run_state_search(), run_state_start(), Search, Start, switch_to_state_done(), landing_target_pose_s::timestamp, and uORB::Subscription::update().
Referenced by Mission::on_active().
|
private |
Definition at line 284 of file precland.cpp.
References NavigatorMode::_navigator, _target_pose, vehicle_global_position_s::alt, position_setpoint_s::alt, check_state_conditions(), position_setpoint_triplet_s::current, DescendAboveTarget, Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, map_projection_reproject(), Navigator::set_position_setpoint_triplet_updated(), switch_to_state_fallback(), switch_to_state_final_approach(), switch_to_state_start(), position_setpoint_s::type, landing_target_pose_s::x_abs, and landing_target_pose_s::y_abs.
Referenced by on_active().
|
private |
Definition at line 361 of file precland.cpp.
Referenced by on_active().
|
private |
Definition at line 321 of file precland.cpp.
Referenced by on_active().
|
private |
Definition at line 220 of file precland.cpp.
References _approach_alt, NavigatorMode::_navigator, _point_reached_time, _state_start_time, _target_pose, vehicle_global_position_s::alt, position_setpoint_s::alt, check_state_conditions(), position_setpoint_triplet_s::current, DescendAboveTarget, Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), HorizontalApproach, hrt_absolute_time(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, map_projection_reproject(), Navigator::set_position_setpoint_triplet_updated(), slewrate(), STATE_TIMEOUT, switch_to_state_descend_above_target(), switch_to_state_fallback(), switch_to_state_start(), position_setpoint_s::type, landing_target_pose_s::x_abs, and landing_target_pose_s::y_abs.
Referenced by on_active().
|
private |
Definition at line 327 of file precland.cpp.
References NavigatorMode::_navigator, _state_start_time, _target_acquired_time, vehicle_global_position_s::alt, position_setpoint_s::alt, check_state_conditions(), position_setpoint_triplet_s::current, Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), HorizontalApproach, hrt_absolute_time(), SEC2USEC, Navigator::set_position_setpoint_triplet_updated(), switch_to_state_fallback(), and switch_to_state_horizontal_approach().
Referenced by on_active().
|
private |
Definition at line 176 of file precland.cpp.
References _mode, NavigatorMode::_navigator, _point_reached_time, position_setpoint_triplet_s::current, get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, Opportunistic, switch_to_state_fallback(), switch_to_state_horizontal_approach(), and switch_to_state_search().
Referenced by on_active().
|
inline |
Definition at line 76 of file precland.h.
References _mode.
Referenced by Navigator::run(), and Mission::set_mission_items().
|
private |
Definition at line 528 of file precland.cpp.
References _last_slewrate_time, NavigatorMode::_navigator, _param_acceleration_hor, _param_xy_vel_cruise, _sp_pev, _sp_pev_prev, position_setpoint_triplet_s::current, dt, Navigator::get_local_position(), Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), position_setpoint_s::lat, matrix::Vector< Type, M >::length(), position_setpoint_s::lon, map_projection_project(), matrix::Vector< Type, M >::normalized(), SEC2USEC, vehicle_local_position_s::vx, and vehicle_local_position_s::vy.
Referenced by run_state_horizontal_approach().
|
private |
Definition at line 402 of file precland.cpp.
References _state, _state_start_time, check_state_conditions(), DescendAboveTarget, and hrt_absolute_time().
Referenced by run_state_horizontal_approach().
|
private |
Definition at line 460 of file precland.cpp.
References _state, _state_start_time, Done, and hrt_absolute_time().
Referenced by on_active().
|
private |
Definition at line 444 of file precland.cpp.
References NavigatorMode::_navigator, _state, _state_start_time, vehicle_global_position_s::alt, position_setpoint_s::alt, position_setpoint_triplet_s::current, Fallback, Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, Navigator::set_position_setpoint_triplet_updated(), and position_setpoint_s::type.
Referenced by run_state_descend_above_target(), run_state_horizontal_approach(), run_state_search(), and run_state_start().
|
private |
Definition at line 414 of file precland.cpp.
References _state, _state_start_time, check_state_conditions(), FinalApproach, and hrt_absolute_time().
Referenced by run_state_descend_above_target().
|
private |
Definition at line 386 of file precland.cpp.
References _approach_alt, NavigatorMode::_navigator, _point_reached_time, _state, _state_start_time, vehicle_global_position_s::alt, check_state_conditions(), Navigator::get_global_position(), HorizontalApproach, and hrt_absolute_time().
Referenced by run_state_search(), and run_state_start().
|
private |
Definition at line 426 of file precland.cpp.
References NavigatorMode::_navigator, _state, _state_start_time, _target_acquired_time, position_setpoint_s::alt, position_setpoint_triplet_s::current, Navigator::get_local_position(), Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), vehicle_local_position_s::ref_alt, Search, Navigator::set_position_setpoint_triplet_updated(), and position_setpoint_s::type.
Referenced by run_state_start().
|
private |
Definition at line 367 of file precland.cpp.
References NavigatorMode::_navigator, _point_reached_time, _search_cnt, _state, _state_start_time, check_state_conditions(), position_setpoint_triplet_s::current, Navigator::get_position_setpoint_triplet(), hrt_absolute_time(), Navigator::set_position_setpoint_triplet_updated(), Start, and position_setpoint_s::type.
Referenced by on_activation(), run_state_descend_above_target(), and run_state_horizontal_approach().
|
overrideprivate |
Definition at line 162 of file precland.cpp.
References _handle_param_xy_vel_cruise, _param_acceleration_hor, _param_xy_vel_cruise, param_get(), and PARAM_INVALID.
Referenced by PrecLand().
|
private |
altitude at which to stay during horizontal approach
Definition at line 119 of file precland.h.
Referenced by run_state_horizontal_approach(), and switch_to_state_horizontal_approach().
|
private |
Definition at line 139 of file precland.h.
Referenced by PrecLand(), and updateParams().
|
private |
time when we last limited setpoint changes
Definition at line 114 of file precland.h.
Referenced by on_activation(), and slewrate().
|
private |
Definition at line 126 of file precland.h.
Referenced by run_state_start().
|
private |
Definition at line 140 of file precland.h.
Referenced by slewrate(), and updateParams().
|
private |
Definition at line 141 of file precland.h.
Referenced by slewrate(), and updateParams().
|
private |
time when we reached a setpoint
Definition at line 116 of file precland.h.
Referenced by run_state_horizontal_approach(), run_state_start(), switch_to_state_horizontal_approach(), and switch_to_state_start().
|
private |
counter of how many times we had to search for the landing target
Definition at line 118 of file precland.h.
Referenced by check_state_conditions(), on_activation(), and switch_to_state_start().
|
private |
Definition at line 121 of file precland.h.
Referenced by on_activation(), and slewrate().
|
private |
Definition at line 122 of file precland.h.
Referenced by on_activation(), and slewrate().
|
private |
Definition at line 124 of file precland.h.
Referenced by check_state_conditions(), on_activation(), on_active(), switch_to_state_descend_above_target(), switch_to_state_done(), switch_to_state_fallback(), switch_to_state_final_approach(), switch_to_state_horizontal_approach(), switch_to_state_search(), and switch_to_state_start().
|
private |
time when we entered current state
Definition at line 113 of file precland.h.
Referenced by run_state_horizontal_approach(), run_state_search(), switch_to_state_descend_above_target(), switch_to_state_done(), switch_to_state_fallback(), switch_to_state_final_approach(), switch_to_state_horizontal_approach(), switch_to_state_search(), and switch_to_state_start().
|
private |
time when we first saw the landing target during search
Definition at line 115 of file precland.h.
Referenced by run_state_search(), and switch_to_state_search().
|
private |
precision landing target position
Definition at line 105 of file precland.h.
Referenced by check_state_conditions(), on_active(), run_state_descend_above_target(), and run_state_horizontal_approach().
|
private |
Definition at line 107 of file precland.h.
Referenced by on_active().
|
private |
wether the landing target position message is updated
Definition at line 109 of file precland.h.
Referenced by check_state_conditions(), and on_active().
|
private |
whether we have received a landing target position message
Definition at line 108 of file precland.h.
Referenced by check_state_conditions(), and on_active().