|
MAV'RIC
|


Classes | |
| struct | conf_t |
Public Member Functions | |
| Mavlink_waypoint_handler (const INS &ins, Mavlink_message_handler &message_handler, const Mavlink_stream &mavlink_stream, Mission_handler_registry &mission_handler_registry, conf_t config=default_config()) | |
| Initialize the waypoint handler. | |
| bool | init () |
| uint16_t | waypoint_count () const |
| Returns the number of waypoints. | |
| uint64_t | waypoint_received_time_ms () const |
| Returns the time that the waypoint list was received. | |
| const Waypoint & | current_waypoint () const |
| Gets the current waypoint. | |
| const Waypoint & | next_waypoint () const |
| Gets the next waypoint if available. | |
| const Waypoint & | waypoint_from_index (int i) const |
| Returns a waypoint from the list from a specific index. | |
| const Waypoint & | home_waypoint () const |
| Returns the home waypoint. | |
| void | advance_to_next_waypoint () |
| Sets the next waypoint as the current one. Should be called when the current waypoint has been reached. | |
| uint16_t | current_waypoint_index () const |
| Gets the current waypoint index. | |
| bool | set_current_waypoint_index (int index) |
| Sets the current waypoint index if possible. | |
Static Public Member Functions | |
| static conf_t | default_config () |
| Default configuration. | |
Protected Attributes | |
| Waypoint | waypoint_list_ [MAX_WAYPOINTS] |
| The array of all waypoints (max MAX_WAYPOINTS) | |
| uint16_t | waypoint_count_ |
| The total number of waypoints. | |
| uint16_t | current_waypoint_index_ |
| The current waypoint index. | |
| Waypoint | home_waypoint_ |
| The home waypoint. | |
| const Mavlink_stream & | mavlink_stream_ |
| The reference to MAVLink stream object. | |
| const INS & | ins_ |
| The pointer to the position estimation structure. | |
| Mavlink_message_handler & | message_handler_ |
| The reference to the mavlink message handler. | |
| Mission_handler_registry & | mission_handler_registry_ |
| The reference to the mission handler registry. | |
| Mavlink_waypoint_handler::Mavlink_waypoint_handler | ( | const INS & | ins, |
| Mavlink_message_handler & | message_handler, | ||
| const Mavlink_stream & | mavlink_stream, | ||
| Mission_handler_registry & | mission_handler_registry, | ||
| conf_t | config = default_config() |
||
| ) |
Initialize the waypoint handler.
| ins | The reference to the Inertial Navigation System |
| message_handler | The reference to the message handler |
| mavlink_stream | The reference to the MAVLink stream structure |
| mission_handler_registry | The reference to the mission handler registry |
| config | The config structure (optional) |
| const Waypoint & Mavlink_waypoint_handler::current_waypoint | ( | ) | const |
Gets the current waypoint.
If there is no waypoints in the list, creates a hold position waypoint as the first index in the list and returns it


| uint16_t Mavlink_waypoint_handler::current_waypoint_index | ( | ) | const |
Gets the current waypoint index.

| Mavlink_waypoint_handler::conf_t Mavlink_waypoint_handler::default_config | ( | void | ) | [inline, static] |
Default configuration.
| const Waypoint & Mavlink_waypoint_handler::home_waypoint | ( | ) | const |
Returns the home waypoint.
Recreates the home waypoint if it has not been manually set as the takeoff altitude could have changed from the onboard parameters

| const Waypoint & Mavlink_waypoint_handler::next_waypoint | ( | ) | const |
Gets the next waypoint if available.
If there is no waypoints in the list, creates a hold position waypoint as the first index in the list and returns it

| bool Mavlink_waypoint_handler::set_current_waypoint_index | ( | int | index | ) |
Sets the current waypoint index if possible.
| index | The new waypoint index |

| uint16_t Mavlink_waypoint_handler::waypoint_count | ( | ) | const [inline] |
Returns the number of waypoints.

| const Waypoint & Mavlink_waypoint_handler::waypoint_from_index | ( | int | i | ) | const |
Returns a waypoint from the list from a specific index.
If there is no waypoints in the list, creates a hold position waypoint as the first index in the list and returns it

| uint64_t Mavlink_waypoint_handler::waypoint_received_time_ms | ( | ) | const [inline] |
Returns the time that the waypoint list was received.
1.7.6.1