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

#include <mission.h>

Inheritance diagram for Mission:
Collaboration diagram for Mission:

Public Types

enum  mission_altitude_mode { MISSION_ALTMODE_ZOH = 0, MISSION_ALTMODE_FOH = 1 }
 

Public Member Functions

 Mission (Navigator *navigator)
 
 ~Mission () override=default
 
void on_inactive () override
 This function is called while the mode is inactive. More...
 
void on_inactivation () override
 This function is called one time when mode becomes 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...
 
bool set_current_mission_index (uint16_t index)
 
bool land_start ()
 
bool landing ()
 
uint16_t get_land_start_index () const
 
bool get_land_start_available () const
 
bool get_mission_finished () const
 
bool get_mission_changed () const
 
bool get_mission_waypoints_changed () const
 
double get_landing_lat ()
 
double get_landing_lon ()
 
float get_landing_alt ()
 
void set_closest_item_as_current ()
 
void set_execution_mode (const uint8_t mode)
 Set a new mission mode and handle the switching between the different modes. More...
 
- Public Member Functions inherited from MissionBlock
 MissionBlock (Navigator *navigator)
 Constructor. More...
 
virtual ~MissionBlock ()=default
 
 MissionBlock (const MissionBlock &)=delete
 
MissionBlockoperator= (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)
 

Private Types

enum  { MISSION_TYPE_NONE, MISSION_TYPE_MISSION }
 
enum  work_item_type {
  WORK_ITEM_TYPE_DEFAULT, WORK_ITEM_TYPE_TAKEOFF, WORK_ITEM_TYPE_MOVE_TO_LAND, WORK_ITEM_TYPE_ALIGN,
  WORK_ITEM_TYPE_CMD_BEFORE_MOVE, WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF, WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION, WORK_ITEM_TYPE_PRECISION_LAND
}
 

Private Member Functions

void update_mission ()
 Update mission topic. More...
 
void advance_mission ()
 Move on to next mission item or switch to loiter. More...
 
void set_mission_items ()
 Set new mission items. More...
 
bool do_need_vertical_takeoff ()
 Returns true if we need to do a takeoff at the current state. More...
 
bool do_need_move_to_land ()
 Returns true if we need to move to waypoint location before starting descent. More...
 
bool do_need_move_to_takeoff ()
 Returns true if we need to move to waypoint location after vtol takeoff. More...
 
void copy_position_if_valid (struct mission_item_s *mission_item, struct position_setpoint_s *setpoint)
 Copies position from setpoint if valid, otherwise copies current position. More...
 
void set_align_mission_item (struct mission_item_s *mission_item, struct mission_item_s *mission_item_next)
 Create mission item to align towards next waypoint. More...
 
float calculate_takeoff_altitude (struct mission_item_s *mission_item)
 Calculate takeoff height for mission item considering ground clearance. More...
 
void heading_sp_update ()
 Updates the heading of the vehicle. More...
 
void altitude_sp_foh_update ()
 Updates the altitude sp to follow a foh. More...
 
void cruising_speed_sp_update ()
 Update the cruising speed setpoint. More...
 
void do_abort_landing ()
 Abort landing. More...
 
bool prepare_mission_items (mission_item_s *mission_item, mission_item_s *next_position_mission_item, bool *has_next_position_item)
 Read the current and the next mission item. More...
 
bool read_mission_item (int offset, struct mission_item_s *mission_item)
 Read current (offset == 0) or a specific (offset > 0) mission item from the dataman and watch out for DO_JUMPS. More...
 
void save_mission_state ()
 Save current mission state to dataman. More...
 
void report_do_jump_mission_changed (int index, int do_jumps_remaining)
 Inform about a changed mission item after a DO_JUMP. More...
 
void set_mission_item_reached ()
 Set a mission item as reached. More...
 
void set_current_mission_item ()
 Set the current mission item. More...
 
void check_mission_valid (bool force)
 Check whether a mission is ready to go. More...
 
void reset_mission (struct mission_s &mission)
 Reset mission. More...
 
bool need_to_reset_mission (bool active)
 Returns true if we need to reset the mission. More...
 
void generate_waypoint_from_heading (struct position_setpoint_s *setpoint, float yaw)
 Project current location with heading to far away location and fill setpoint. More...
 
bool find_mission_land_start ()
 Find and store the index of the landing sequence (DO_LAND_START) More...
 
int32_t index_closest_mission_item () const
 Return the index of the closest mission item to the current global position. More...
 
bool position_setpoint_equal (const position_setpoint_s *p1, const position_setpoint_s *p2) const
 

Private Attributes

DEFINE_PARAMETERS((ParamFloat< px4::params::MIS_DIST_1WP >) _param_mis_dist_1wp,(ParamFloat< px4::params::MIS_DIST_WPS >) _param_mis_dist_wps,(ParamInt< px4::params::MIS_ALTMODE >) _param_mis_altmode,(ParamInt< px4::params::MIS_MNT_YAW_CTL >) _param_mis_mnt_yaw_ctl) uORB mission_s _mission {}
 < mission subscription More...
 
int32_t _current_mission_index {-1}
 
bool _land_start_available {false}
 
uint16_t _land_start_index {UINT16_MAX}
 index of DO_LAND_START, INVALID_DO_LAND_START if no planned landing More...
 
double _landing_lat {0.0}
 
double _landing_lon {0.0}
 
float _landing_alt {0.0f}
 
bool _need_takeoff {true}
 if true, then takeoff must be performed before going to the first waypoint (if needed) More...
 
enum Mission:: { ... }  MISSION_TYPE_NONE
 
bool _inited {false}
 
bool _home_inited {false}
 
bool _need_mission_reset {false}
 
bool _mission_waypoints_changed {false}
 
bool _mission_changed {false}
 
float _min_current_sp_distance_xy {FLT_MAX}
 < true if the mission changed since the mission mode was active More...
 
float _distance_current_previous {0.0f}
 distance from previous to current sp in pos_sp_triplet, only use if current and previous are valid More...
 
enum Mission::work_item_type WORK_ITEM_TYPE_DEFAULT
 current type of work to do (sub mission item) More...
 
uint8_t _mission_execution_mode {mission_result_s::MISSION_EXECUTION_MODE_NORMAL}
 the current mode of how the mission is executed,look at mission_result.msg for the definition More...
 
bool _execution_mode_changed {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}
 

Detailed Description

Definition at line 68 of file mission.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
private
Enumerator
MISSION_TYPE_NONE 
MISSION_TYPE_MISSION 

Definition at line 263 of file mission.h.

◆ mission_altitude_mode

Enumerator
MISSION_ALTMODE_ZOH 
MISSION_ALTMODE_FOH 

Definition at line 79 of file mission.h.

◆ work_item_type

Enumerator
WORK_ITEM_TYPE_DEFAULT 

default mission item

WORK_ITEM_TYPE_TAKEOFF 

takeoff before moving to waypoint

WORK_ITEM_TYPE_MOVE_TO_LAND 

move to land waypoint before descent

WORK_ITEM_TYPE_ALIGN 

align for next waypoint

WORK_ITEM_TYPE_CMD_BEFORE_MOVE 
WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF 
WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION 
WORK_ITEM_TYPE_PRECISION_LAND 

Definition at line 279 of file mission.h.

Constructor & Destructor Documentation

◆ Mission()

Mission::Mission ( Navigator navigator)

Definition at line 62 of file mission.cpp.

◆ ~Mission()

Mission::~Mission ( )
overridedefault

Member Function Documentation

◆ advance_mission()

void Mission::advance_mission ( )
private

Move on to next mission item or switch to loiter.

Definition at line 533 of file mission.cpp.

References _current_mission_index, _mission, _mission_execution_mode, mission_s::dataman_id, dm_read(), MissionBlock::item_contains_position(), MISSION_TYPE_MISSION, MISSION_TYPE_NONE, and WORK_ITEM_TYPE_DEFAULT.

Referenced by get_landing_alt(), and on_active().

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

◆ altitude_sp_foh_update()

◆ calculate_takeoff_altitude()

float Mission::calculate_takeoff_altitude ( struct mission_item_s mission_item)
private

Calculate takeoff height for mission item considering ground clearance.

Definition at line 1206 of file mission.cpp.

References NavigatorMode::_navigator, home_position_s::alt, vehicle_global_position_s::alt, MissionBlock::get_absolute_altitude_for_item(), Navigator::get_global_position(), Navigator::get_home_position(), Navigator::get_land_detected(), Navigator::get_takeoff_min_alt(), and vehicle_land_detected_s::landed.

Referenced by do_need_vertical_takeoff(), get_landing_alt(), and set_mission_items().

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

◆ check_mission_valid()

void Mission::check_mission_valid ( bool  force)
private

Check whether a mission is ready to go.

Definition at line 1651 of file mission.cpp.

References _home_inited, _mission, NavigatorMode::_navigator, MissionFeasibilityChecker::checkMissionFeasible(), mission_s::count, find_mission_land_start(), Navigator::get_mission_result(), Navigator::home_position_valid(), Navigator::increment_mission_instance_count(), Navigator::mission_landing_required(), mission_result_s::seq_total, Navigator::set_mission_result_updated(), and mission_result_s::valid.

Referenced by get_landing_alt(), on_active(), on_inactive(), and update_mission().

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

◆ copy_position_if_valid()

void Mission::copy_position_if_valid ( struct mission_item_s mission_item,
struct position_setpoint_s setpoint 
)
private

Copies position from setpoint if valid, otherwise copies current position.

Definition at line 1175 of file mission.cpp.

References NavigatorMode::_navigator, vehicle_global_position_s::alt, position_setpoint_s::alt, mission_item_s::altitude, mission_item_s::altitude_is_relative, Navigator::get_global_position(), vehicle_global_position_s::lat, position_setpoint_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, mission_item_s::lon, position_setpoint_s::type, and position_setpoint_s::valid.

Referenced by get_landing_alt(), set_align_mission_item(), and set_mission_items().

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

◆ cruising_speed_sp_update()

void Mission::cruising_speed_sp_update ( )
private

Update the cruising speed setpoint.

Definition at line 1365 of file mission.cpp.

References NavigatorMode::_navigator, position_setpoint_s::cruising_speed, position_setpoint_triplet_s::current, FLT_EPSILON, Navigator::get_cruising_speed(), Navigator::get_position_setpoint_triplet(), Navigator::set_position_setpoint_triplet_updated(), and position_setpoint_s::valid.

Referenced by get_landing_alt(), and on_active().

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

◆ do_abort_landing()

void Mission::do_abort_landing ( )
private

Abort landing.

Definition at line 1383 of file mission.cpp.

References _current_mission_index, _land_start_available, MissionBlock::_mission_item, NavigatorMode::_navigator, mission_item_s::acceptance_radius, vehicle_global_position_s::alt, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, vehicle_command_s::command, position_setpoint_triplet_s::current, MissionBlock::get_absolute_altitude_for_item(), Navigator::get_acceptance_radius(), Navigator::get_global_position(), get_land_start_index(), Navigator::get_loiter_min_alt(), Navigator::get_loiter_radius(), Navigator::get_mavlink_log_pub(), Navigator::get_position_setpoint_triplet(), mission_item_s::lat, mission_item_s::loiter_radius, mission_item_s::lon, mavlink_and_console_log_info, math::max(), MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), mission_item_s::nav_cmd, NAV_CMD_LAND, NAV_CMD_LOITER_UNLIMITED, mission_item_s::origin, ORIGIN_ONBOARD, vehicle_command_s::param1, vehicle_command_s::param2, vehicle_command_s::param5, vehicle_command_s::param6, vehicle_command_s::param7, Navigator::publish_vehicle_cmd(), and Navigator::set_position_setpoint_triplet_updated().

Referenced by get_landing_alt(), and on_active().

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

◆ do_need_move_to_land()

bool Mission::do_need_move_to_land ( )
private

Returns true if we need to move to waypoint location before starting descent.

Definition at line 1145 of file mission.cpp.

References MissionBlock::_mission_item, NavigatorMode::_navigator, Navigator::get_acceptance_radius(), get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_vstatus(), vehicle_global_position_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_LAND, NAV_CMD_VTOL_LAND, and vehicle_status_s::vehicle_type.

Referenced by get_landing_alt(), and set_mission_items().

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

◆ do_need_move_to_takeoff()

bool Mission::do_need_move_to_takeoff ( )
private

Returns true if we need to move to waypoint location after vtol takeoff.

Definition at line 1160 of file mission.cpp.

References MissionBlock::_mission_item, NavigatorMode::_navigator, Navigator::get_acceptance_radius(), get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_vstatus(), vehicle_global_position_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_VTOL_TAKEOFF, and vehicle_status_s::vehicle_type.

Referenced by get_landing_alt(), and set_mission_items().

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

◆ do_need_vertical_takeoff()

bool Mission::do_need_vertical_takeoff ( )
private

Returns true if we need to do a takeoff at the current state.

Definition at line 1107 of file mission.cpp.

References MissionBlock::_mission_item, NavigatorMode::_navigator, _need_takeoff, vehicle_global_position_s::alt, calculate_takeoff_altitude(), Navigator::get_altitude_acceptance_radius(), Navigator::get_global_position(), Navigator::get_land_detected(), Navigator::get_vstatus(), vehicle_land_detected_s::landed, mission_item_s::nav_cmd, NAV_CMD_LOITER_TIME_LIMIT, NAV_CMD_LOITER_UNLIMITED, NAV_CMD_TAKEOFF, NAV_CMD_VTOL_TAKEOFF, NAV_CMD_WAYPOINT, and vehicle_status_s::vehicle_type.

Referenced by get_landing_alt(), and set_mission_items().

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

◆ find_mission_land_start()

bool Mission::find_mission_land_start ( )
private

Find and store the index of the landing sequence (DO_LAND_START)

Definition at line 379 of file mission.cpp.

References _mission, and mission_s::dataman_id.

Referenced by check_mission_valid(), get_landing_alt(), on_inactive(), and update_mission().

Here is the caller graph for this function:

◆ generate_waypoint_from_heading()

void Mission::generate_waypoint_from_heading ( struct position_setpoint_s setpoint,
float  yaw 
)
private

Project current location with heading to far away location and fill setpoint.

Definition at line 1740 of file mission.cpp.

References NavigatorMode::_navigator, Navigator::get_global_position(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, position_setpoint_s::type, waypoint_from_heading_and_distance(), position_setpoint_s::yaw, and mission_item_s::yaw.

Referenced by get_landing_alt(), set_execution_mode(), and set_mission_items().

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

◆ get_land_start_available()

bool Mission::get_land_start_available ( ) const
inline

Definition at line 90 of file mission.h.

References _land_start_available.

Referenced by Navigator::get_mission_start_land_available(), and Navigator::run().

Here is the caller graph for this function:

◆ get_land_start_index()

uint16_t Mission::get_land_start_index ( ) const
inline

Definition at line 89 of file mission.h.

References _land_start_index.

Referenced by do_abort_landing(), Navigator::get_mission_landing_index(), land_start(), landing(), and Navigator::run().

Here is the caller graph for this function:

◆ get_landing_alt()

◆ get_landing_lat()

double Mission::get_landing_lat ( )
inline

Definition at line 94 of file mission.h.

References _landing_lat.

Referenced by Navigator::get_mission_landing_lat().

Here is the caller graph for this function:

◆ get_landing_lon()

double Mission::get_landing_lon ( )
inline

Definition at line 95 of file mission.h.

References _landing_lon.

Referenced by Navigator::get_mission_landing_lon().

Here is the caller graph for this function:

◆ get_mission_changed()

bool Mission::get_mission_changed ( ) const
inline

Definition at line 92 of file mission.h.

References _mission_changed.

Referenced by Navigator::run().

Here is the caller graph for this function:

◆ get_mission_finished()

bool Mission::get_mission_finished ( ) const
inline

Definition at line 91 of file mission.h.

References MISSION_TYPE_NONE.

Referenced by Navigator::run().

Here is the caller graph for this function:

◆ get_mission_waypoints_changed()

bool Mission::get_mission_waypoints_changed ( ) const
inline

Definition at line 93 of file mission.h.

References _mission_waypoints_changed.

Referenced by Navigator::run().

Here is the caller graph for this function:

◆ heading_sp_update()

void Mission::heading_sp_update ( )
private

Updates the heading of the vehicle.

Rotary wings only.

Definition at line 1223 of file mission.cpp.

References MissionBlock::_mission_item, NavigatorMode::_navigator, position_setpoint_triplet_s::current, Navigator::get_acceptance_radius(), get_bearing_to_next_waypoint(), get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), Navigator::get_vroi(), vehicle_global_position_s::lat, vehicle_roi_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, vehicle_roi_s::lon, position_setpoint_s::lon, vehicle_roi_s::mode, Navigator::set_position_setpoint_triplet_updated(), position_setpoint_s::valid, matrix::wrap_pi(), position_setpoint_s::yaw, mission_item_s::yaw, vehicle_roi_s::yaw_offset, and position_setpoint_s::yaw_valid.

Referenced by get_landing_alt(), and on_active().

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

◆ index_closest_mission_item()

int32_t Mission::index_closest_mission_item ( ) const
private

Return the index of the closest mission item to the current global position.

Definition at line 1751 of file mission.cpp.

References _mission, _mission_execution_mode, NavigatorMode::_navigator, vehicle_global_position_s::alt, home_position_s::alt, mission_s::count, mission_s::dataman_id, dm_read(), MissionBlock::get_absolute_altitude_for_item(), get_distance_to_point_global_wgs84(), Navigator::get_global_position(), Navigator::get_home_position(), Navigator::get_vstatus(), vehicle_status_s::is_vtol, MissionBlock::item_contains_position(), vehicle_global_position_s::lat, home_position_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, home_position_s::lon, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_LAND, vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.

Referenced by get_landing_alt(), on_activation(), on_active(), and set_closest_item_as_current().

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

◆ land_start()

bool Mission::land_start ( )

Definition at line 429 of file mission.cpp.

References _land_start_available, get_land_start_index(), landing(), and set_current_mission_index().

Referenced by Navigator::run(), and Navigator::start_mission_landing().

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

◆ landing()

bool Mission::landing ( )

Definition at line 446 of file mission.cpp.

References _current_mission_index, _land_start_available, NavigatorMode::_navigator, get_land_start_index(), Navigator::get_mission_result(), and mission_result_s::valid.

Referenced by land_start(), and Navigator::on_mission_landing().

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

◆ need_to_reset_mission()

bool Mission::need_to_reset_mission ( bool  active)
private

Returns true if we need to reset the mission.

Definition at line 1724 of file mission.cpp.

References NavigatorMode::_navigator, _need_mission_reset, vehicle_status_s::arming_state, and Navigator::get_vstatus().

Referenced by get_landing_alt(), on_active(), and on_inactive().

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

◆ on_activation()

void Mission::on_activation ( )
overridevirtual

This function is called one time when mode becomes active, pos_sp_triplet must be initialized here.

Reimplemented from NavigatorMode.

Definition at line 149 of file mission.cpp.

References _current_mission_index, _execution_mode_changed, _mission_execution_mode, _mission_waypoints_changed, NavigatorMode::_navigator, vehicle_command_s::command, index_closest_mission_item(), vehicle_command_s::param1, vehicle_command_s::param3, Navigator::publish_vehicle_cmd(), and set_mission_items().

Here is the call graph for this function:

◆ on_active()

void Mission::on_active ( )
overridevirtual

This function is called while the mode is active.

Reimplemented from NavigatorMode.

Definition at line 175 of file mission.cpp.

References _current_mission_index, _execution_mode_changed, _mission, _mission_changed, _mission_execution_mode, MissionBlock::_mission_item, _mission_waypoints_changed, NavigatorMode::_navigator, MissionBlock::_waypoint_position_reached, Navigator::abort_landing(), advance_mission(), altitude_sp_foh_update(), mission_item_s::autocontinue, check_mission_valid(), cruising_speed_sp_update(), do_abort_landing(), Navigator::get_land_detected(), Navigator::get_precland(), Navigator::get_vroi(), Navigator::get_vstatus(), heading_sp_update(), index_closest_mission_item(), MissionBlock::is_mission_item_reached(), vehicle_land_detected_s::landed, MISSION_ALTMODE_FOH, MISSION_TYPE_NONE, vehicle_roi_s::mode, mission_item_s::nav_cmd, NAV_CMD_DO_VTOL_TRANSITION, NAV_CMD_IDLE, NAV_CMD_LAND, NAV_CMD_TAKEOFF, NAV_CMD_VTOL_LAND, NAV_CMD_VTOL_TAKEOFF, need_to_reset_mission(), PrecLand::on_active(), NavigatorMode::on_inactivation(), Navigator::reset_cruising_speed(), reset_mission(), Navigator::reset_triplets(), Navigator::set_can_loiter_at_sp(), set_mission_item_reached(), set_mission_items(), update_mission(), vehicle_status_s::vehicle_type, WORK_ITEM_TYPE_ALIGN, WORK_ITEM_TYPE_DEFAULT, WORK_ITEM_TYPE_PRECISION_LAND, and WORK_ITEM_TYPE_TAKEOFF.

Here is the call graph for this function:

◆ on_inactivation()

void Mission::on_inactivation ( )
overridevirtual

This function is called one time when mode becomes inactive.

Reimplemented from NavigatorMode.

Definition at line 137 of file mission.cpp.

References NavigatorMode::_navigator, vehicle_command_s::command, vehicle_command_s::param1, vehicle_command_s::param3, and Navigator::publish_vehicle_cmd().

Here is the call graph for this function:

◆ on_inactive()

◆ position_setpoint_equal()

◆ prepare_mission_items()

bool Mission::prepare_mission_items ( mission_item_s mission_item,
mission_item_s next_position_mission_item,
bool *  has_next_position_item 
)
private

Read the current and the next mission item.

The next mission item read is the next mission item that contains a position.

Returns
true if current mission item available

Definition at line 1437 of file mission.cpp.

References _mission_execution_mode, MissionBlock::item_contains_position(), and read_mission_item().

Referenced by get_landing_alt(), and set_mission_items().

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

◆ read_mission_item()

bool Mission::read_mission_item ( int  offset,
struct mission_item_s mission_item 
)
private

Read current (offset == 0) or a specific (offset > 0) mission item from the dataman and watch out for DO_JUMPS.

Returns
true if successful

Definition at line 1474 of file mission.cpp.

References _current_mission_index, _mission, _mission_execution_mode, NavigatorMode::_navigator, mission_s::count, mission_s::dataman_id, DM_PERSIST_POWER_ON_RESET, dm_read(), dm_write(), mission_item_s::do_jump_current_count, mission_item_s::do_jump_mission_index, mission_item_s::do_jump_repeat_count, Navigator::get_mavlink_log_pub(), mavlink_log_critical, mavlink_log_info, mission_item_s::nav_cmd, NAV_CMD_DO_JUMP, and report_do_jump_mission_changed().

Referenced by get_landing_alt(), and prepare_mission_items().

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

◆ report_do_jump_mission_changed()

void Mission::report_do_jump_mission_changed ( int  index,
int  do_jumps_remaining 
)
private

Inform about a changed mission item after a DO_JUMP.

Definition at line 1620 of file mission.cpp.

References NavigatorMode::_navigator, Navigator::get_mission_result(), mission_result_s::item_changed_index, mission_result_s::item_do_jump_changed, mission_result_s::item_do_jump_remaining, and Navigator::set_mission_result_updated().

Referenced by get_landing_alt(), and read_mission_item().

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

◆ reset_mission()

void Mission::reset_mission ( struct mission_s mission)
private

Reset mission.

Definition at line 1674 of file mission.cpp.

References NavigatorMode::_navigator, mission_s::count, mission_s::current_seq, mission_s::dataman_id, DM_KEY_MISSION_STATE, DM_KEY_WAYPOINTS_OFFBOARD_0, DM_KEY_WAYPOINTS_OFFBOARD_1, dm_lock(), DM_PERSIST_POWER_ON_RESET, dm_read(), dm_unlock(), dm_write(), mission_item_s::do_jump_current_count, Navigator::get_mavlink_log_pub(), hrt_absolute_time(), mavlink_log_critical, mission_item_s::nav_cmd, NAV_CMD_DO_JUMP, and mission_s::timestamp.

Referenced by get_landing_alt(), on_active(), and on_inactive().

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

◆ save_mission_state()

void Mission::save_mission_state ( )
private

Save current mission state to dataman.

Definition at line 1566 of file mission.cpp.

References _current_mission_index, _mission, NavigatorMode::_navigator, mission_s::count, mission_s::current_seq, mission_s::dataman_id, DM_KEY_MISSION_STATE, dm_lock(), DM_PERSIST_POWER_ON_RESET, dm_read(), dm_unlock(), dm_write(), Navigator::get_mavlink_log_pub(), hrt_absolute_time(), mavlink_log_critical, and mission_s::timestamp.

Referenced by get_landing_alt(), and set_current_mission_item().

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

◆ set_align_mission_item()

void Mission::set_align_mission_item ( struct mission_item_s mission_item,
struct mission_item_s mission_item_next 
)
private

Create mission item to align towards next waypoint.

Definition at line 1192 of file mission.cpp.

References NavigatorMode::_navigator, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, copy_position_if_valid(), position_setpoint_triplet_s::current, mission_item_s::force_heading, get_bearing_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_position_setpoint_triplet(), vehicle_global_position_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_WAYPOINT, mission_item_s::time_inside, and mission_item_s::yaw.

Referenced by get_landing_alt(), and set_mission_items().

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

◆ set_closest_item_as_current()

void Mission::set_closest_item_as_current ( )

Definition at line 309 of file mission.cpp.

References _current_mission_index, and index_closest_mission_item().

Referenced by get_landing_alt(), and Navigator::run().

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

◆ set_current_mission_index()

bool Mission::set_current_mission_index ( uint16_t  index)

Definition at line 282 of file mission.cpp.

References _current_mission_index, _mission, _mission_waypoints_changed, NavigatorMode::_navigator, mission_s::count, position_setpoint_triplet_s::current, Navigator::get_mission_result(), Navigator::get_position_setpoint_triplet(), Navigator::is_planned_mission(), position_setpoint_triplet_s::next, position_setpoint_triplet_s::previous, set_mission_items(), mission_result_s::valid, and position_setpoint_s::valid.

Referenced by land_start(), and Navigator::run().

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

◆ set_current_mission_item()

void Mission::set_current_mission_item ( )
private

Set the current mission item.

Definition at line 1640 of file mission.cpp.

References _current_mission_index, NavigatorMode::_navigator, mission_result_s::finished, Navigator::get_mission_result(), save_mission_state(), mission_result_s::seq_current, and Navigator::set_mission_result_updated().

Referenced by get_landing_alt(), set_mission_items(), and update_mission().

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

◆ set_execution_mode()

void Mission::set_execution_mode ( const uint8_t  mode)

Set a new mission mode and handle the switching between the different modes.

For a list of the different modes refer to mission_result.msg

Definition at line 315 of file mission.cpp.

References _current_mission_index, _execution_mode_changed, _mission, _mission_execution_mode, MissionBlock::_mission_item, NavigatorMode::_navigator, mission_s::count, position_setpoint_triplet_s::current, mission_result_s::execution_mode, generate_waypoint_from_heading(), Navigator::get_land_detected(), Navigator::get_mission_result(), Navigator::get_position_setpoint_triplet(), Navigator::get_vstatus(), vehicle_status_s::is_vtol, MissionBlock::issue_command(), vehicle_land_detected_s::landed, MISSION_TYPE_MISSION, MISSION_TYPE_NONE, position_setpoint_triplet_s::previous, Navigator::set_position_setpoint_triplet_updated(), MissionBlock::set_vtol_transition_item(), vehicle_status_s::vehicle_type, WORK_ITEM_TYPE_DEFAULT, and mission_item_s::yaw.

Referenced by get_landing_alt(), and Navigator::run().

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

◆ set_mission_item_reached()

void Mission::set_mission_item_reached ( )
private

Set a mission item as reached.

Definition at line 1631 of file mission.cpp.

References _current_mission_index, NavigatorMode::_navigator, Navigator::get_mission_result(), MissionBlock::reset_mission_item_reached(), mission_result_s::seq_reached, and Navigator::set_mission_result_updated().

Referenced by get_landing_alt(), and on_active().

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

◆ set_mission_items()

void Mission::set_mission_items ( )
private

Set new mission items.

Definition at line 587 of file mission.cpp.

References _distance_current_previous, _min_current_sp_distance_xy, _mission_execution_mode, MissionBlock::_mission_item, NavigatorMode::_navigator, _need_takeoff, position_setpoint_s::allow_weather_vane, home_position_s::alt, vehicle_global_position_s::alt, position_setpoint_s::alt, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, calculate_takeoff_altitude(), copy_position_if_valid(), position_setpoint_triplet_s::current, do_need_move_to_land(), do_need_move_to_takeoff(), do_need_vertical_takeoff(), mission_result_s::finished, FLT_EPSILON, mission_item_s::force_heading, Navigator::force_vtol(), generate_waypoint_from_heading(), get_bearing_to_next_waypoint(), get_distance_to_next_waypoint(), Navigator::get_global_position(), Navigator::get_home_position(), Navigator::get_land_detected(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_result(), Navigator::get_position_setpoint_triplet(), Navigator::get_precland(), Navigator::get_takeoff_min_alt(), MissionBlock::get_time_inside(), Navigator::get_vstatus(), MissionBlock::issue_command(), MissionBlock::item_contains_position(), mission_item_s::land_precision, vehicle_land_detected_s::landed, vehicle_global_position_s::lat, position_setpoint_s::lat, mission_item_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, mission_item_s::lon, mavlink_log_critical, mavlink_log_info, MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), MISSION_TYPE_MISSION, MISSION_TYPE_NONE, mission_item_s::nav_cmd, NAV_CMD_DELAY, NAV_CMD_DO_VTOL_TRANSITION, NAV_CMD_LAND, NAV_CMD_LOITER_TIME_LIMIT, NAV_CMD_LOITER_UNLIMITED, NAV_CMD_TAKEOFF, NAV_CMD_VTOL_LAND, NAV_CMD_VTOL_TAKEOFF, NAV_CMD_WAYPOINT, position_setpoint_triplet_s::next, PrecLand::on_activation(), Opportunistic, position_setpoint_equal(), prepare_mission_items(), position_setpoint_triplet_s::previous, Required, MissionBlock::reset_mission_item_reached(), set_align_mission_item(), Navigator::set_can_loiter_at_sp(), set_current_mission_item(), MissionBlock::set_loiter_item(), Navigator::set_mission_result_updated(), PrecLand::set_mode(), Navigator::set_position_setpoint_triplet_updated(), MissionBlock::set_vtol_transition_item(), mission_item_s::time_inside, position_setpoint_s::type, position_setpoint_s::valid, vehicle_status_s::vehicle_type, VEHICLE_TYPE_FIXED_WING, mission_item_s::vtol_back_transition, WORK_ITEM_TYPE_ALIGN, WORK_ITEM_TYPE_CMD_BEFORE_MOVE, WORK_ITEM_TYPE_DEFAULT, WORK_ITEM_TYPE_MOVE_TO_LAND, WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION, WORK_ITEM_TYPE_PRECISION_LAND, WORK_ITEM_TYPE_TAKEOFF, WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF, vehicle_global_position_s::yaw, position_setpoint_s::yaw, and mission_item_s::yaw.

Referenced by get_landing_alt(), on_activation(), on_active(), and set_current_mission_index().

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

◆ update_mission()

void Mission::update_mission ( )
private

Update mission topic.

Definition at line 458 of file mission.cpp.

References _current_mission_index, _mission, _mission_changed, _mission_waypoints_changed, NavigatorMode::_navigator, check_mission_valid(), mission_s::count, mission_s::current_seq, mission_s::dataman_id, mission_result_s::failure, find_mission_land_start(), Navigator::get_land_detected(), Navigator::get_mission_result(), vehicle_land_detected_s::landed, Navigator::reset_vroi(), mission_result_s::seq_reached, mission_result_s::seq_total, set_current_mission_item(), mission_result_s::valid, and WORK_ITEM_TYPE_DEFAULT.

Referenced by get_landing_alt(), on_active(), and on_inactive().

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

Member Data Documentation

◆ _current_mission_index

◆ _distance_current_previous

float Mission::_distance_current_previous {0.0f}
private

distance from previous to current sp in pos_sp_triplet, only use if current and previous are valid

Definition at line 276 of file mission.h.

Referenced by altitude_sp_foh_update(), and set_mission_items().

◆ _execution_mode_changed

bool Mission::_execution_mode_changed {false}
private

Definition at line 291 of file mission.h.

Referenced by on_activation(), on_active(), and set_execution_mode().

◆ _home_inited

bool Mission::_home_inited {false}
private

Definition at line 269 of file mission.h.

Referenced by check_mission_valid().

◆ _inited

bool Mission::_inited {false}
private

Definition at line 268 of file mission.h.

Referenced by on_inactive().

◆ _land_start_available

bool Mission::_land_start_available {false}
private

Definition at line 255 of file mission.h.

Referenced by do_abort_landing(), get_land_start_available(), land_start(), and landing().

◆ _land_start_index

uint16_t Mission::_land_start_index {UINT16_MAX}
private

index of DO_LAND_START, INVALID_DO_LAND_START if no planned landing

Definition at line 256 of file mission.h.

Referenced by get_land_start_index().

◆ _landing_alt

float Mission::_landing_alt {0.0f}
private

Definition at line 259 of file mission.h.

Referenced by get_landing_alt().

◆ _landing_lat

double Mission::_landing_lat {0.0}
private

Definition at line 257 of file mission.h.

Referenced by get_landing_lat().

◆ _landing_lon

double Mission::_landing_lon {0.0}
private

Definition at line 258 of file mission.h.

Referenced by get_landing_lon().

◆ _min_current_sp_distance_xy

float Mission::_min_current_sp_distance_xy {FLT_MAX}
private

< true if the mission changed since the mission mode was active

minimum distance which was achieved to the current waypoint

Definition at line 274 of file mission.h.

Referenced by altitude_sp_foh_update(), and set_mission_items().

◆ _mission

DEFINE_PARAMETERS ( (ParamFloat<px4::params::MIS_DIST_1WP>) _param_mis_dist_1wp, (ParamFloat<px4::params::MIS_DIST_WPS>) _param_mis_dist_wps, (ParamInt<px4::params::MIS_ALTMODE>) _param_mis_altmode, (ParamInt<px4::params::MIS_MNT_YAW_CTL>) _param_mis_mnt_yaw_ctl ) uORB mission_s Mission::_mission {}
private

◆ _mission_changed

bool Mission::_mission_changed {false}
private

Definition at line 272 of file mission.h.

Referenced by get_mission_changed(), on_active(), and update_mission().

◆ _mission_execution_mode

uint8_t Mission::_mission_execution_mode {mission_result_s::MISSION_EXECUTION_MODE_NORMAL}
private

the current mode of how the mission is executed,look at mission_result.msg for the definition

Definition at line 290 of file mission.h.

Referenced by advance_mission(), index_closest_mission_item(), on_activation(), on_active(), prepare_mission_items(), read_mission_item(), set_execution_mode(), and set_mission_items().

◆ _mission_waypoints_changed

bool Mission::_mission_waypoints_changed {false}
private

◆ _need_mission_reset

bool Mission::_need_mission_reset {false}
private

Definition at line 270 of file mission.h.

Referenced by need_to_reset_mission().

◆ _need_takeoff

bool Mission::_need_takeoff {true}
private

if true, then takeoff must be performed before going to the first waypoint (if needed)

Definition at line 261 of file mission.h.

Referenced by do_need_vertical_takeoff(), on_inactive(), and set_mission_items().

◆ MISSION_TYPE_NONE

enum { ... } Mission::MISSION_TYPE_NONE

◆ WORK_ITEM_TYPE_DEFAULT

enum Mission::work_item_type Mission::WORK_ITEM_TYPE_DEFAULT
private

current type of work to do (sub mission item)

Referenced by advance_mission(), on_active(), on_inactive(), set_execution_mode(), set_mission_items(), and update_mission().


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