#include <AP_Navigation.h>
Definition at line 14 of file AP_Navigation.h.
◆ ControllerType
Enumerator |
---|
CONTROLLER_DEFAULT | |
CONTROLLER_L1 | |
Definition at line 122 of file AP_Navigation.h.
◆ bearing_error_cd()
virtual int32_t AP_Navigation::bearing_error_cd |
( |
void |
| ) |
const |
|
pure virtual |
◆ crosstrack_error()
virtual float AP_Navigation::crosstrack_error |
( |
void |
| ) |
const |
|
pure virtual |
◆ crosstrack_error_integrator()
virtual float AP_Navigation::crosstrack_error_integrator |
( |
void |
| ) |
const |
|
inlinevirtual |
◆ data_is_stale()
virtual bool AP_Navigation::data_is_stale |
( |
void |
| ) |
const |
|
pure virtual |
◆ lateral_acceleration()
virtual float AP_Navigation::lateral_acceleration |
( |
void |
| ) |
const |
|
pure virtual |
◆ loiter_radius()
virtual float AP_Navigation::loiter_radius |
( |
const float |
radius | ) |
const |
|
pure virtual |
◆ nav_bearing_cd()
virtual int32_t AP_Navigation::nav_bearing_cd |
( |
void |
| ) |
const |
|
pure virtual |
◆ nav_roll_cd()
virtual int32_t AP_Navigation::nav_roll_cd |
( |
void |
| ) |
const |
|
pure virtual |
◆ reached_loiter_target()
virtual bool AP_Navigation::reached_loiter_target |
( |
void |
| ) |
|
|
pure virtual |
◆ set_data_is_stale()
virtual void AP_Navigation::set_data_is_stale |
( |
void |
| ) |
|
|
pure virtual |
◆ set_reverse()
virtual void AP_Navigation::set_reverse |
( |
bool |
reverse | ) |
|
|
pure virtual |
◆ target_bearing_cd()
virtual int32_t AP_Navigation::target_bearing_cd |
( |
void |
| ) |
const |
|
pure virtual |
◆ turn_distance() [1/2]
virtual float AP_Navigation::turn_distance |
( |
float |
wp_radius | ) |
const |
|
pure virtual |
◆ turn_distance() [2/2]
virtual float AP_Navigation::turn_distance |
( |
float |
wp_radius, |
|
|
float |
turn_angle |
|
) |
| const |
|
pure virtual |
◆ update_heading_hold()
virtual void AP_Navigation::update_heading_hold |
( |
int32_t |
navigation_heading_cd | ) |
|
|
pure virtual |
◆ update_level_flight()
virtual void AP_Navigation::update_level_flight |
( |
void |
| ) |
|
|
pure virtual |
◆ update_loiter()
virtual void AP_Navigation::update_loiter |
( |
const struct Location & |
center_WP, |
|
|
float |
radius, |
|
|
int8_t |
loiter_direction |
|
) |
| |
|
pure virtual |
◆ update_waypoint()
virtual void AP_Navigation::update_waypoint |
( |
const struct Location & |
prev_WP, |
|
|
const struct Location & |
next_WP, |
|
|
float |
dist_min = 0.0f |
|
) |
| |
|
pure virtual |
The documentation for this class was generated from the following file: