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

List of all members.

Public Member Functions

 Mission_handler_takeoff (const INS &ins, State &state)
 Initialize the takeoff mission planner handler.
virtual bool can_handle (const Waypoint &wpt) const
 Checks if the waypoint is a takeoff waypoint.
virtual bool setup (const Waypoint &wpt)
 Sets up this handler class for a first time initialization.
virtual
Mission_handler::update_status_t 
update ()
 Handles the mission every iteration.
virtual bool write_flight_command (Flight_controller &flight_controller) const
 Provides control commands to the flight controller.
virtual
Mission_planner::internal_state_t 
handler_mission_state () const
 Returns that the mission state is in PREMISSION.

Protected Attributes

const INSins_
 The reference to the ins interface.
Statestate_
 The reference to the state structure.
Waypoint waypoint_
 The take off waypoint.

Constructor & Destructor Documentation

Initialize the takeoff mission planner handler.

Parameters:
insThe reference to the ins
stateThe reference to the state class

Member Function Documentation

bool Mission_handler_takeoff::can_handle ( const Waypoint wpt) const [virtual]

Checks if the waypoint is a takeoff waypoint.

Checks if the inputted waypoint is a: MAV_CMD_NAV_TAKEOFF

Parameters:
wptThe waypoint class
Returns:
Can handle

Implements Mission_handler.

Here is the call graph for this function:

Mission_planner::internal_state_t Mission_handler_takeoff::handler_mission_state ( ) const [virtual]

Returns that the mission state is in PREMISSION.

Returns:
Mission handler's mission state

Implements Mission_handler.

bool Mission_handler_takeoff::setup ( const Waypoint wpt) [virtual]

Sets up this handler class for a first time initialization.

Records the waypoint reference and sets the mav mode

Parameters:
wptThe waypoint class
Returns:
Success

Implements Mission_handler.

Here is the call graph for this function:

Mission_handler::update_status_t Mission_handler_takeoff::update ( void  ) [virtual]

Handles the mission every iteration.

Sets the goal and determines the handler status. The status is: MISSION_IN_PROGRESS for takeoff in process, MISSION_FINISHED for takeoff complete, and MISSION_FAILED for control impossible

Returns:
Status code

Implements Mission_handler.

Here is the call graph for this function:

bool Mission_handler_takeoff::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