AP_InertialSensor: Set the gravitational acceleration value to the defined value

This commit is contained in:
murata 2020-03-15 12:25:25 +09:00 committed by Randy Mackay
parent 2eee8e389d
commit 219dc2e7da
1 changed files with 1 additions and 1 deletions

View File

@ -90,7 +90,7 @@ const extern AP_HAL::HAL &hal;
#define ACCEL_DEFAULT_RANGE_G 8
#define ACCEL_DEFAULT_RATE 1000
#define ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 780
#define ACCEL_ONE_G 9.80665f
#define ACCEL_ONE_G GRAVITY_MSS
/************************************i3g4250d register addresses *******************************************/
#define GYRO_WHO_AM_I 0x0F