mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: Make get_z_accel_cmss public
This commit is contained in:
parent
a8bf2c0141
commit
4a12faea92
|
@ -387,6 +387,9 @@ public:
|
|||
/// aircraft when in standby.
|
||||
void standby_xyz_reset();
|
||||
|
||||
// get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up
|
||||
float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
|
@ -394,9 +397,6 @@ protected:
|
|||
// get throttle using vibration-resistant calculation (uses feed forward with manually calculated gain)
|
||||
float get_throttle_with_vibration_override();
|
||||
|
||||
// get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up
|
||||
float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; }
|
||||
|
||||
// lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
|
||||
void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const;
|
||||
|
||||
|
|
Loading…
Reference in New Issue