|
MAV'RIC
|


Public Member Functions | |
| Mission_handler_hold_position (const INS &ins) | |
| Initialize the hold position mission planner handler. | |
| virtual bool | can_handle (const Waypoint &wpt) const |
| Checks if the waypoint is a hold position 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 MISSION. | |
Protected Attributes | |
| Waypoint | waypoint_ |
| Pointer to the inputted waypoint. | |
| uint64_t | start_time_ |
| The start time of the waypoint hold. | |
| bool | within_radius_ |
| Flag stating if we are within the radius. | |
| const INS & | ins_ |
| The reference to the ins structure. | |
| Mission_handler_hold_position::Mission_handler_hold_position | ( | const INS & | ins | ) |
Initialize the hold position mission planner handler.
| ins | The reference to the ins |
| bool Mission_handler_hold_position::can_handle | ( | const Waypoint & | wpt | ) | const [virtual] |
Checks if the waypoint is a hold position waypoint.
Checks if this is a: MAV_CMD_NAV_LOITER_UNLIM MAV_CMD_NAV_LOITER_TIME MAV_CMD_NAV_LOITER_TO_ALT MAV_CMD_OVERRIDE_GOTO if param1 == MAV_GOTO_DO_HOLD
| wpt | The waypoint class |
Implements Mission_handler.

| Mission_planner::internal_state_t Mission_handler_hold_position::handler_mission_state | ( | ) | const [virtual] |
Returns that the mission state is in MISSION.
Implements Mission_handler.
| bool Mission_handler_hold_position::setup | ( | const Waypoint & | wpt | ) | [virtual] |
Sets up this handler class for a first time initialization.
Stores the waypoint reference and records the starting time
| wpt | The waypoint class |
Implements Mission_handler.
| Mission_handler::update_status_t Mission_handler_hold_position::update | ( | void | ) | [virtual] |
Handles the mission every iteration.
Sets the waypoint goal to the setup waypoint. Returns MISSION_IN_PROGRESS if the drone is still holding position, MISSION_FINISHED if it should move to the next waypoint, and MISSION_FAILED if the drone cannot hold position
Implements Mission_handler.

| bool Mission_handler_hold_position::write_flight_command | ( | Flight_controller & | flight_controller | ) | const [virtual] |
Provides control commands to the flight controller.
Implements Flight_command_source.

1.7.6.1