mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
INS: switch to global definition of GRAVITY_MSS
saves 4 bytes of RAM
This commit is contained in:
parent
fc0c451b69
commit
af13f6795c
@ -286,8 +286,7 @@ AP_InertialSensor::_init_accel(void (*flash_leds_cb)(bool on))
|
||||
}
|
||||
|
||||
// null gravity from the Z accel
|
||||
// TO-DO: replace with gravity #define form location.cpp
|
||||
accel_offset.z += GRAVITY;
|
||||
accel_offset.z += GRAVITY_MSS;
|
||||
|
||||
total_change = fabsf(prev.x - accel_offset.x) + fabsf(prev.y - accel_offset.y) + fabsf(prev.z - accel_offset.z);
|
||||
max_offset = (accel_offset.x > accel_offset.y) ? accel_offset.x : accel_offset.y;
|
||||
@ -422,7 +421,7 @@ bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6],
|
||||
|
||||
// reset
|
||||
beta[0] = beta[1] = beta[2] = 0;
|
||||
beta[3] = beta[4] = beta[5] = 1.0f/GRAVITY;
|
||||
beta[3] = beta[4] = beta[5] = 1.0f/GRAVITY_MSS;
|
||||
|
||||
while( num_iterations < 20 && change > eps ) {
|
||||
num_iterations++;
|
||||
@ -452,9 +451,9 @@ bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6],
|
||||
}
|
||||
|
||||
// copy results out
|
||||
accel_scale.x = beta[3] * GRAVITY;
|
||||
accel_scale.y = beta[4] * GRAVITY;
|
||||
accel_scale.z = beta[5] * GRAVITY;
|
||||
accel_scale.x = beta[3] * GRAVITY_MSS;
|
||||
accel_scale.y = beta[4] * GRAVITY_MSS;
|
||||
accel_scale.z = beta[5] * GRAVITY_MSS;
|
||||
accel_offsets.x = beta[0] * accel_scale.x;
|
||||
accel_offsets.y = beta[1] * accel_scale.y;
|
||||
accel_offsets.z = beta[2] * accel_scale.z;
|
||||
|
@ -3,7 +3,6 @@
|
||||
#ifndef __AP_INERTIAL_SENSOR_H__
|
||||
#define __AP_INERTIAL_SENSOR_H__
|
||||
|
||||
#define GRAVITY 9.80665f
|
||||
// Gyro and Accelerometer calibration criteria
|
||||
#define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
|
||||
#define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f
|
||||
|
@ -6,7 +6,7 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// MPU6000 accelerometer scaling
|
||||
#define MPU6000_ACCEL_SCALE_1G (GRAVITY / 4096.0f)
|
||||
#define MPU6000_ACCEL_SCALE_1G (GRAVITY_MSS / 4096.0f)
|
||||
|
||||
// MPU 6000 registers
|
||||
#define MPUREG_XG_OFFS_TC 0x00
|
||||
|
@ -24,7 +24,7 @@ const float AP_InertialSensor_Oilpan::_adc_constraint = 900;
|
||||
// Tested value : 418
|
||||
|
||||
// Oilpan accelerometer scaling & offsets
|
||||
#define OILPAN_ACCEL_SCALE_1G (GRAVITY * 2.0f / (2465.0f - 1617.0f))
|
||||
#define OILPAN_ACCEL_SCALE_1G (GRAVITY_MSS * 2.0f / (2465.0f - 1617.0f))
|
||||
#define OILPAN_RAW_ACCEL_OFFSET ((2465.0f + 1617.0f) * 0.5f)
|
||||
#define OILPAN_RAW_GYRO_OFFSET 1658.0f
|
||||
|
||||
|
@ -39,8 +39,6 @@ private:
|
||||
static const int8_t _sensor_signs[6];
|
||||
static const uint8_t _gyro_temp_ch;
|
||||
|
||||
static const float _gravity;
|
||||
|
||||
static const float _gyro_gain_x;
|
||||
static const float _gyro_gain_y;
|
||||
static const float _gyro_gain_z;
|
||||
|
Loading…
Reference in New Issue
Block a user