mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: use shared GRAVITY_MSS constant
This commit is contained in:
parent
0aff1136ed
commit
777c6a308e
|
@ -304,7 +304,7 @@ static bool waypoint_valid(Location &wp)
|
|||
static void
|
||||
get_loiter_accel(int16_t accel_req_forward, int16_t accel_req_right)
|
||||
{
|
||||
float z_accel_meas = -AP_INTERTIALNAV_GRAVITY * 100; // gravity in cm/s/s
|
||||
float z_accel_meas = -GRAVITY_MSS * 100; // gravity in cm/s/s
|
||||
|
||||
// update angle targets that will be passed to stabilize controller
|
||||
auto_roll = constrain((accel_req_right/(-z_accel_meas))*(18000/M_PI), -4500, 4500);
|
||||
|
|
|
@ -51,7 +51,7 @@ void AP_InertialNav::update(float dt)
|
|||
accel_ef = _ahrs->get_accel_ef();
|
||||
|
||||
// remove influence of gravity
|
||||
accel_ef.z += AP_INTERTIALNAV_GRAVITY;
|
||||
accel_ef.z += GRAVITY_MSS;
|
||||
accel_ef *= 100;
|
||||
|
||||
// remove xy if not enabled
|
||||
|
|
|
@ -8,7 +8,6 @@
|
|||
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
|
||||
#include <AP_Buffer.h> // FIFO buffer library
|
||||
|
||||
#define AP_INTERTIALNAV_GRAVITY 9.80665f
|
||||
#define AP_INTERTIALNAV_TC_XY 3.0f // default time constant for complementary filter's X & Y axis
|
||||
#define AP_INTERTIALNAV_TC_Z 5.0f // default time constant for complementary filter's Z axis
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@ const extern AP_HAL::HAL& hal;
|
|||
|
||||
AP_InertialSensor_Stub::AP_InertialSensor_Stub() {
|
||||
Vector3f accels;
|
||||
accels.z = -9.808;
|
||||
accels.z = -GRAVITY_MSS;
|
||||
set_accel(accels);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue