MAV'RIC
Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes
Mission_planner Class Reference
Inheritance diagram for Mission_planner:
Inheritance graph
[legend]
Collaboration diagram for Mission_planner:
Collaboration graph
[legend]

List of all members.

Classes

struct  conf_t

Public Types

enum  internal_state_t {
  STANDBY, PREMISSION, MISSION, POSTMISSION,
  PAUSED, MANUAL_CTRL
}
enum  critical_behavior_enum { CLIMB_TO_SAFE_ALT, FLY_TO_HOME_WP, HOME_LAND, CRITICAL_LAND }
 The critical behavior enum. More...

Public Member Functions

 Mission_planner (INS &ins, const AHRS &ahrs, State &state, const Manual_control &manual_control, const Geofence &geofence, Mavlink_message_handler &message_handler, const Mavlink_stream &mavlink_stream, Mavlink_waypoint_handler &waypoint_handler, Mission_handler_registry &mission_handler_registry, conf_t config=default_config())
 Initialize the waypoint handler.
bool init ()
bool write_flight_command (Flight_controller &flight_controller) const
 Provides control commands to the flight controller.
void set_critical_next_state (bool critical_next_state)
internal_state_t internal_state () const
 Gets the internal state.
critical_behavior_enum critical_behavior () const
 Returns the critical behavior.
bool switch_mission_handler (const Waypoint &waypoint)
 Switches the mission handler to the inputted waypoint.
bool insert_ad_hoc_waypoint (Waypoint wpt)
 Inserts the inputted waypoint into the mission.
float & takeoff_altitude ()
 Gets the reference to the takeoff altitude.

Static Public Member Functions

static bool update (Mission_planner *mission_planner)
 The mission planner tasks, gives a goal for the navigation module.
static conf_t default_config ()
 Default configuration.

Protected Member Functions

void state_machine ()
 State machine to drive the navigation module.
void critical_handler ()
 Drives the critical navigation behavior.
void set_internal_state (internal_state_t new_internal_state)
 Sets the internal state based on default waypoints.
bool set_current_waypoint (uint16_t index)
 Sets the current waypoint to num_of_waypoint.

Static Protected Member Functions

static void mission_set_current_callback (Mission_planner *mission_planner, uint32_t sysid, const mavlink_message_t *msg)
 Set the current waypoint to new_current.
static mav_result_t nav_go_home (Mission_planner *mission_planner, const mavlink_command_long_t *packet)
 Navigate to the home position and hold.
static mav_result_t mission_start_callback (Mission_planner *mission_planner, const mavlink_command_long_t *packet)
 Starts the mission.
static mav_result_t nav_takeoff_callback (Mission_planner *mission_planner, const mavlink_command_long_t *packet)
 Sets auto-takeoff procedure from a MAVLink command message MAV_CMD_NAV_TAKEOFF.
static mav_result_t nav_land_callback (Mission_planner *mission_planner, const mavlink_command_long_t *packet)
 Drives the auto landing procedure from the MAV_CMD_NAV_LAND message long.
static mav_result_t override_goto_callback (Mission_planner *mission_planner, const mavlink_command_long_t *packet)
 Pauses the navigation or resumes/advances the navigation waypoint.

Protected Attributes

Mission_handlercurrent_mission_handler_
 The currently used mission handler.
Waypoint inserted_waypoint_
 A waypoint that is inserted into the plan outside of the normal mission.
internal_state_t internal_state_
 The internal state of the navigation module.
critical_behavior_enum critical_behavior_
 The critical behavior enum.
Mavlink_waypoint_handlerwaypoint_handler_
 The reference to the mavlink waypoint handler.
Mission_handler_registrymission_handler_registry_
 The reference to the mission handler registry.
bool require_takeoff_
 Flag stating if we require takeoff when switching to auto, set when not auto.
bool hold_position_set_
 Flag stating if the pilot has specifically switched to hold position.
bool critical_next_state_
 Flag to change critical state in its dedicated state machine.
Waypoint critical_waypoint_
 Waypoint for the critical state.
const Mavlink_streammavlink_stream_
 The reference to MAVLink stream.
Statestate_
 The reference to the state structure.
INSins_
 The reference to the ins structure.
const AHRSahrs_
 The reference to the attitude estimation structure.
const Manual_controlmanual_control_
 The reference to the manual_control structure.
const Geofencegeofence_
 The reference to the geofence structure.
Mavlink_message_handlermessage_handler_
 The reference to the mavlink message handler.
conf_t config_

Member Enumeration Documentation

The critical behavior enum.

Enumerator:
CLIMB_TO_SAFE_ALT 

First critical behavior.

FLY_TO_HOME_WP 

Second critical behavior, comes after Navigation::CLIMB_TO_SAFE_ALT.

HOME_LAND 

Third critical behavior, comes after Navigation::FLY_TO_HOME_WP.

CRITICAL_LAND 

Fourth critical behavior.


Constructor & Destructor Documentation

Mission_planner::Mission_planner ( INS ins,
const AHRS ahrs,
State state,
const Manual_control manual_control,
const Geofence geofence,
Mavlink_message_handler message_handler,
const Mavlink_stream mavlink_stream,
Mavlink_waypoint_handler waypoint_handler,
Mission_handler_registry mission_handler_registry,
conf_t  config = default_config() 
)

Initialize the waypoint handler.

Parameters:
insThe reference to the ins structure
ahrsThe reference to the attitude estimation structure
stateThe reference to the state structure
manual_controlThe reference to the manual control structure
geofenceThe reference to the geofence structure
mavlink_communicationThe reference to the MAVLink communication structure
mavlink_streamThe reference to the MAVLink stream structure
waypoint_handlerThe handler for the waypoints
mission_handler_registryThe reference to the mission handler registry
Returns:
True if the init succeed, false otherwise

Member Function Documentation

Returns the critical behavior.

Returns:
Critical behavior

Default configuration.

Returns:
Config structure

Inserts the inputted waypoint into the mission.

This inserts a waypoint into the mission and sets the internal state to paused. If the insert fails, the function returns false and does not set the mission handler or inserted waypoint

Parameters:
wptThe waypoint
Returns:
Success

Here is the call graph for this function:

Here is the caller graph for this function:

Mission_planner::internal_state_t Mission_planner::internal_state ( ) const

Gets the internal state.

Returns:
internal_state_

Here is the caller graph for this function:

void Mission_planner::mission_set_current_callback ( Mission_planner mission_planner,
uint32_t  sysid,
const mavlink_message_t *  msg 
) [static, protected]

Set the current waypoint to new_current.

Parameters:
mission_plannerThe pointer to the mission planner class
sysidThe system ID
msgThe received MAVLink message structure with the number of the current waypoint

Here is the call graph for this function:

mav_result_t Mission_planner::mission_start_callback ( Mission_planner mission_planner,
const mavlink_command_long_t *  packet 
) [static, protected]

Starts the mission.

Parameters:
mission_plannerThe pointer to the mission planner class
sysidThe system ID
msgThe received MAVLink message structure with the number of the current waypoint

Here is the call graph for this function:

mav_result_t Mission_planner::nav_go_home ( Mission_planner mission_planner,
const mavlink_command_long_t *  packet 
) [static, protected]

Navigate to the home position and hold.

N.B. Intentionally mislabelled to go to home, not return to launch

Parameters:
mission_plannerThe pointer to the object of the Mission planner takeoff handler
packetThe pointer to the structure of the MAVLink command message long
Returns:
The MAV_RESULT of the command

Here is the call graph for this function:

mav_result_t Mission_planner::nav_land_callback ( Mission_planner mission_planner,
const mavlink_command_long_t *  packet 
) [static, protected]

Drives the auto landing procedure from the MAV_CMD_NAV_LAND message long.

Parameters:
mission_plannerThe pointer to the structure of the MAVLink waypoint handler
packetThe pointer to the structure of the MAVLink command message long
Returns:
The MAV_RESULT of the command

Here is the call graph for this function:

mav_result_t Mission_planner::nav_takeoff_callback ( Mission_planner mission_planner,
const mavlink_command_long_t *  packet 
) [static, protected]

Sets auto-takeoff procedure from a MAVLink command message MAV_CMD_NAV_TAKEOFF.

Parameters:
mission_plannerThe pointer to the object of the Mission planner takeoff handler
packetThe pointer to the structure of the MAVLink command message long
Returns:
The MAV_RESULT of the command

Here is the call graph for this function:

mav_result_t Mission_planner::override_goto_callback ( Mission_planner mission_planner,
const mavlink_command_long_t *  packet 
) [static, protected]

Pauses the navigation or resumes/advances the navigation waypoint.

Parameters:
navigating_handlerThe pointer to the structure of the navigating handler
packetThe pointer to the structure of the MAVLink command message long
Returns:
The MAV_RESULT of the command

Here is the call graph for this function:

bool Mission_planner::set_current_waypoint ( uint16_t  index) [protected]

Sets the current waypoint to num_of_waypoint.

Parameters:
sysidThe system ID
msgThe received MAVLink message structure with the number of the current waypoint

Here is the call graph for this function:

Here is the caller graph for this function:

void Mission_planner::set_internal_state ( internal_state_t  new_internal_state) [protected]

Sets the internal state based on default waypoints.

THIS SHOULD NOT BE SET AS A METHOD TO CHANGE THE MISSION HANDLER! USE Mission_planner::switch_mission_handler() or Mission_planner::insert_ad_hoc_waypoint()

Parameters:
new_internal_stateThe new internal state

Here is the caller graph for this function:

Switches the mission handler to the inputted waypoint.

The current mission handler is set based on the inputted waypoint. If the mission handler could not be setup or found, no change is made to the current mission handler

Parameters:
waypoint
Returns:
Success

Here is the call graph for this function:

Here is the caller graph for this function:

float& Mission_planner::takeoff_altitude ( ) [inline]

Gets the reference to the takeoff altitude.

Returns:
Takeoff altitude
bool Mission_planner::update ( Mission_planner mission_planner) [static]

The mission planner tasks, gives a goal for the navigation module.

Parameters:
mission_plannerThe pointer to the waypoint handler structure

Here is the call graph for this function:

bool Mission_planner::write_flight_command ( Flight_controller flight_controller) const [virtual]

Provides control commands to the flight controller.

Returns:
success

Implements Flight_command_source.

Here is the call graph for this function:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines