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

#include <mission_feasibility_checker.h>

Collaboration diagram for MissionFeasibilityChecker:

Public Member Functions

 MissionFeasibilityChecker (Navigator *navigator)
 
 ~MissionFeasibilityChecker ()=default
 
 MissionFeasibilityChecker (const MissionFeasibilityChecker &)=delete
 
MissionFeasibilityCheckeroperator= (const MissionFeasibilityChecker &)=delete
 
bool checkMissionFeasible (const mission_s &mission, float max_distance_to_1st_waypoint, float max_distance_between_waypoints, bool land_start_req)
 

Private Member Functions

bool checkGeofence (const mission_s &mission, float home_alt, bool home_valid)
 
bool checkHomePositionAltitude (const mission_s &mission, float home_alt, bool home_alt_valid, bool throw_error)
 
bool checkMissionItemValidity (const mission_s &mission)
 
bool checkDistanceToFirstWaypoint (const mission_s &mission, float max_distance)
 
bool checkDistancesBetweenWaypoints (const mission_s &mission, float max_distance)
 
bool checkFixedwing (const mission_s &mission, float home_alt, bool land_start_req)
 
bool checkTakeoff (const mission_s &mission, float home_alt)
 
bool checkFixedWingLanding (const mission_s &mission, bool land_start_req)
 
bool checkRotarywing (const mission_s &mission, float home_alt)
 

Private Attributes

Navigator_navigator {nullptr}
 

Detailed Description

Definition at line 51 of file mission_feasibility_checker.h.

Constructor & Destructor Documentation

◆ MissionFeasibilityChecker() [1/2]

MissionFeasibilityChecker::MissionFeasibilityChecker ( Navigator navigator)
inline

Definition at line 75 of file mission_feasibility_checker.h.

References checkMissionFeasible(), operator=(), and ~MissionFeasibilityChecker().

Here is the call graph for this function:

◆ ~MissionFeasibilityChecker()

MissionFeasibilityChecker::~MissionFeasibilityChecker ( )
default

Referenced by MissionFeasibilityChecker().

Here is the caller graph for this function:

◆ MissionFeasibilityChecker() [2/2]

MissionFeasibilityChecker::MissionFeasibilityChecker ( const MissionFeasibilityChecker )
delete

Member Function Documentation

◆ checkDistancesBetweenWaypoints()

bool MissionFeasibilityChecker::checkDistancesBetweenWaypoints ( const mission_s mission,
float  max_distance 
)
private

Definition at line 570 of file mission_feasibility_checker.cpp.

References _navigator, mission_s::count, mission_s::dataman_id, dm_read(), f(), get_distance_to_next_waypoint(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_result(), MissionBlock::item_contains_position(), mission_item_s::lat, mission_item_s::lon, mavlink_log_critical, mavlink_log_info, and mission_result_s::warning.

Referenced by checkMissionFeasible().

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

◆ checkDistanceToFirstWaypoint()

bool MissionFeasibilityChecker::checkDistanceToFirstWaypoint ( const mission_s mission,
float  max_distance 
)
private

Definition at line 522 of file mission_feasibility_checker.cpp.

References _navigator, mission_s::count, mission_s::dataman_id, dm_read(), f(), get_distance_to_next_waypoint(), Navigator::get_home_position(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_result(), MissionBlock::item_contains_position(), home_position_s::lat, mission_item_s::lat, home_position_s::lon, mission_item_s::lon, mavlink_log_critical, mavlink_log_info, and mission_result_s::warning.

Referenced by checkMissionFeasible().

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

◆ checkFixedwing()

bool MissionFeasibilityChecker::checkFixedwing ( const mission_s mission,
float  home_alt,
bool  land_start_req 
)
private

Definition at line 108 of file mission_feasibility_checker.cpp.

References checkFixedWingLanding(), and checkTakeoff().

Referenced by checkMissionFeasible().

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

◆ checkFixedWingLanding()

bool MissionFeasibilityChecker::checkFixedWingLanding ( const mission_s mission,
bool  land_start_req 
)
private

Definition at line 403 of file mission_feasibility_checker.cpp.

References _navigator, mission_item_s::altitude, mission_s::count, mission_s::dataman_id, dm_read(), get_distance_to_next_waypoint(), Navigator::get_mavlink_log_pub(), Landingslope::getLandingSlopeAbsoluteAltitude(), Landingslope::getLandingSlopeWPDistance(), MissionBlock::item_contains_position(), mission_item_s::lat, mission_item_s::lon, mavlink_log_critical, mission_item_s::nav_cmd, NAV_CMD_DO_LAND_START, NAV_CMD_LAND, and ORB_ID.

Referenced by checkFixedwing().

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

◆ checkGeofence()

bool MissionFeasibilityChecker::checkGeofence ( const mission_s mission,
float  home_alt,
bool  home_valid 
)
private

Definition at line 119 of file mission_feasibility_checker.cpp.

References _navigator, Geofence::check(), mission_s::count, mission_s::dataman_id, dm_read(), Navigator::get_geofence(), Navigator::get_mavlink_log_pub(), Geofence::isHomeRequired(), MissionBlock::item_contains_position(), mavlink_log_critical, and Geofence::valid().

Referenced by checkMissionFeasible().

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

◆ checkHomePositionAltitude()

bool MissionFeasibilityChecker::checkHomePositionAltitude ( const mission_s mission,
float  home_alt,
bool  home_alt_valid,
bool  throw_error 
)
private

Definition at line 157 of file mission_feasibility_checker.cpp.

References _navigator, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_s::count, mission_s::dataman_id, dm_read(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_result(), MissionBlock::item_contains_position(), mavlink_log_critical, and mission_result_s::warning.

Referenced by checkMissionFeasible().

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

◆ checkMissionFeasible()

bool MissionFeasibilityChecker::checkMissionFeasible ( const mission_s mission,
float  max_distance_to_1st_waypoint,
float  max_distance_between_waypoints,
bool  land_start_req 
)

Definition at line 57 of file mission_feasibility_checker.cpp.

References _navigator, home_position_s::alt, checkDistancesBetweenWaypoints(), checkDistanceToFirstWaypoint(), checkFixedwing(), checkGeofence(), checkHomePositionAltitude(), checkMissionItemValidity(), checkRotarywing(), Navigator::get_home_position(), Navigator::get_mavlink_log_pub(), Navigator::get_vstatus(), Navigator::home_alt_valid(), Navigator::home_position_valid(), vehicle_status_s::is_vtol, mavlink_log_info, and vehicle_status_s::vehicle_type.

Referenced by Mission::check_mission_valid(), and MissionFeasibilityChecker().

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

◆ checkMissionItemValidity()

bool MissionFeasibilityChecker::checkMissionItemValidity ( const mission_s mission)
private

◆ checkRotarywing()

bool MissionFeasibilityChecker::checkRotarywing ( const mission_s mission,
float  home_alt 
)
private

Definition at line 98 of file mission_feasibility_checker.cpp.

References checkTakeoff().

Referenced by checkMissionFeasible().

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

◆ checkTakeoff()

bool MissionFeasibilityChecker::checkTakeoff ( const mission_s mission,
float  home_alt 
)
private

◆ operator=()

MissionFeasibilityChecker& MissionFeasibilityChecker::operator= ( const MissionFeasibilityChecker )
delete

Referenced by MissionFeasibilityChecker().

Here is the caller graph for this function:

Member Data Documentation

◆ _navigator


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