PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <rtl.h>
Classes | |
struct | RTLPosition |
Public Types | |
enum | RTLType { RTL_HOME = 0, RTL_LAND, RTL_MISSION, RTL_CLOSEST } |
enum | RTLDestinationType { RTL_DESTINATION_HOME = 0, RTL_DESTINATION_MISSION_LANDING, RTL_DESTINATION_SAFE_POINT } |
Public Member Functions | |
RTL (Navigator *navigator) | |
~RTL ()=default | |
void | on_inactive () override |
This function is called while the mode is inactive. More... | |
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 | find_RTL_destination () |
void | set_return_alt_min (bool min) |
int | rtl_type () const |
int | rtl_destination () |
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_inactivation () |
This function is called one time when mode becomes inactive. More... | |
Private Types | |
enum | RTLState { RTL_STATE_NONE = 0, RTL_STATE_CLIMB, RTL_STATE_RETURN, RTL_STATE_TRANSITION_TO_MC, RTL_STATE_DESCEND, RTL_STATE_LOITER, RTL_STATE_LAND, RTL_STATE_LANDED } |
Private Member Functions | |
void | set_rtl_item () |
Set the RTL item. More... | |
void | advance_rtl () |
Move to next RTL item. More... | |
float | calculate_return_alt_from_cone_half_angle (float cone_half_angle_deg) |
Private Attributes | |
enum RTL::RTLState | RTL_STATE_NONE |
RTLPosition | _destination {} |
the RTL position to fly to (typically the home position or a safe point) More... | |
float | _rtl_alt {0.0f} |
bool | _rtl_alt_min {false} |
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} |
|
private |
enum RTL::RTLType |
|
default |
|
private |
Move to next RTL item.
Definition at line 423 of file rtl.cpp.
References NavigatorMode::_navigator, DELAY_SIGMA, Navigator::get_vstatus(), vehicle_status_s::is_vtol, RTL_STATE_CLIMB, RTL_STATE_DESCEND, RTL_STATE_LAND, RTL_STATE_LANDED, RTL_STATE_LOITER, RTL_STATE_RETURN, RTL_STATE_TRANSITION_TO_MC, vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.
Referenced by on_active().
|
private |
Definition at line 477 of file rtl.cpp.
References _destination, NavigatorMode::_navigator, vehicle_global_position_s::alt, RTL::RTLPosition::alt, math::constrain(), f(), get_distance_to_next_waypoint(), Navigator::get_global_position(), vehicle_global_position_s::lat, RTL::RTLPosition::lat, vehicle_global_position_s::lon, RTL::RTLPosition::lon, math::max(), and math::radians().
Referenced by on_activation().
void RTL::find_RTL_destination | ( | ) |
Definition at line 66 of file rtl.cpp.
References _destination, NavigatorMode::_navigator, home_position_s::alt, RTL::RTLPosition::alt, DM_KEY_SAFE_POINTS, dm_read(), Navigator::get_global_position(), Navigator::get_home_position(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_landing_alt(), Navigator::get_mission_landing_lat(), Navigator::get_mission_landing_lon(), Navigator::get_mission_start_land_available(), home_position_s::lat, vehicle_global_position_s::lat, RTL::RTLPosition::lat, mission_safe_point_s::lat, home_position_s::lon, vehicle_global_position_s::lon, RTL::RTLPosition::lon, mission_safe_point_s::lon, mavlink_log_critical, mission_stats_entry_s::num_items, RTL_CLOSEST, RTL_DESTINATION_HOME, RTL_DESTINATION_MISSION_LANDING, RTL_DESTINATION_SAFE_POINT, RTL_HOME, RTL_MISSION, rtl_type(), RTL::RTLPosition::set(), RTL::RTLPosition::type, home_position_s::yaw, and RTL::RTLPosition::yaw.
Referenced by on_inactive().
|
overridevirtual |
This function is called one time when mode becomes active, pos_sp_triplet must be initialized here.
Reimplemented from NavigatorMode.
Definition at line 177 of file rtl.cpp.
References _destination, NavigatorMode::_navigator, _rtl_alt, _rtl_alt_min, vehicle_global_position_s::alt, RTL::RTLPosition::alt, calculate_return_alt_from_cone_half_angle(), Navigator::get_global_position(), Navigator::get_land_detected(), Navigator::get_mavlink_log_pub(), vehicle_land_detected_s::landed, mavlink_and_console_log_info, Navigator::on_mission_landing(), RTL_DESTINATION_HOME, RTL_DESTINATION_MISSION_LANDING, RTL_DESTINATION_SAFE_POINT, RTL_STATE_CLIMB, RTL_STATE_LANDED, RTL_STATE_RETURN, set_rtl_item(), and RTL::RTLPosition::type.
|
overridevirtual |
This function is called while the mode is active.
Reimplemented from NavigatorMode.
Definition at line 221 of file rtl.cpp.
References advance_rtl(), MissionBlock::is_mission_item_reached(), RTL_STATE_LANDED, and set_rtl_item().
|
overridevirtual |
This function is called while the mode is inactive.
Reimplemented from NavigatorMode.
Definition at line 56 of file rtl.cpp.
References find_RTL_destination(), and RTL_STATE_NONE.
int RTL::rtl_destination | ( | ) |
int RTL::rtl_type | ( | ) | const |
Definition at line 171 of file rtl.cpp.
Referenced by find_RTL_destination(), Navigator::mission_landing_required(), and Navigator::rtl_type().
void RTL::set_return_alt_min | ( | bool | min | ) |
Definition at line 230 of file rtl.cpp.
References _rtl_alt_min, and math::min().
Referenced by Navigator::check_traffic(), and set_rtl_item().
|
private |
Set the RTL item.
Definition at line 236 of file rtl.cpp.
References _destination, MissionBlock::_mission_item, NavigatorMode::_navigator, _rtl_alt, mission_item_s::acceptance_radius, vehicle_global_position_s::alt, RTL::RTLPosition::alt, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, position_setpoint_triplet_s::current, FLT_EPSILON, Navigator::get_acceptance_radius(), get_bearing_to_next_waypoint(), get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_local_position(), Navigator::get_loiter_radius(), Navigator::get_mavlink_log_pub(), Navigator::get_position_setpoint_triplet(), MissionBlock::get_time_inside(), Navigator::get_vstatus(), vehicle_status_s::is_vtol, MissionBlock::issue_command(), MissionBlock::item_contains_position(), vehicle_global_position_s::lat, RTL::RTLPosition::lat, mission_item_s::lat, mission_item_s::loiter_radius, vehicle_global_position_s::lon, RTL::RTLPosition::lon, mission_item_s::lon, mavlink_and_console_log_info, mavlink_log_critical, math::max(), math::min(), MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), mission_item_s::nav_cmd, NAV_CMD_LAND, NAV_CMD_LOITER_TIME_LIMIT, NAV_CMD_LOITER_UNLIMITED, NAV_CMD_WAYPOINT, mission_item_s::origin, ORIGIN_ONBOARD, position_setpoint_triplet_s::previous, MissionBlock::reset_mission_item_reached(), RTL_DESTINATION_MISSION_LANDING, RTL_STATE_CLIMB, RTL_STATE_DESCEND, RTL_STATE_LAND, RTL_STATE_LANDED, RTL_STATE_LOITER, RTL_STATE_RETURN, RTL_STATE_TRANSITION_TO_MC, Navigator::set_can_loiter_at_sp(), MissionBlock::set_idle_item(), Navigator::set_position_setpoint_triplet_updated(), set_return_alt_min(), MissionBlock::set_vtol_transition_item(), Navigator::start_mission_landing(), mission_item_s::time_inside, RTL::RTLPosition::type, position_setpoint_s::valid, vehicle_local_position_s::yaw, RTL::RTLPosition::yaw, and mission_item_s::yaw.
Referenced by on_activation(), and on_active().
|
private |
the RTL position to fly to (typically the home position or a safe point)
Definition at line 129 of file rtl.h.
Referenced by calculate_return_alt_from_cone_half_angle(), find_RTL_destination(), on_activation(), and set_rtl_item().
|
private |
Definition at line 131 of file rtl.h.
Referenced by on_activation(), and set_rtl_item().
|
private |
Definition at line 132 of file rtl.h.
Referenced by on_activation(), and set_return_alt_min().
|
private |
Referenced by on_inactive().