mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AC_WPNav: get_terrain_offset and get_vector_NEU made public
This commit is contained in:
parent
80b90a7ac3
commit
d22f8fbc35
@ -49,6 +49,13 @@ public:
|
||||
};
|
||||
AC_WPNav::TerrainSource get_terrain_source() const;
|
||||
|
||||
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
|
||||
bool get_terrain_offset(float& offset_cm);
|
||||
|
||||
// convert location to vector from ekf origin. terrain_alt is set to true if resulting vector's z-axis should be treated as alt-above-terrain
|
||||
// returns false if conversion failed (likely because terrain data was not available)
|
||||
bool get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_alt);
|
||||
|
||||
///
|
||||
/// waypoint controller
|
||||
///
|
||||
@ -216,13 +223,6 @@ protected:
|
||||
uint8_t wp_yaw_set : 1; // true if yaw target has been set
|
||||
} _flags;
|
||||
|
||||
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
|
||||
bool get_terrain_offset(float& offset_cm);
|
||||
|
||||
// convert location to vector from ekf origin. terrain_alt is set to true if resulting vector's z-axis should be treated as alt-above-terrain
|
||||
// returns false if conversion failed (likely because terrain data was not available)
|
||||
bool get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_alt);
|
||||
|
||||
// helper function to calculate scurve jerk and jerk_time values
|
||||
// updates _scurve_jerk and _scurve_jerk_time
|
||||
void calc_scurve_jerk_and_jerk_time();
|
||||
|
Loading…
Reference in New Issue
Block a user