Skip to content

Commit

Permalink
Fix IMU sensitivities
Browse files Browse the repository at this point in the history
The values I found and thought were the normal-mode sensitivies were in fact
specific only to the calibration procedure.
  • Loading branch information
kierdavis committed Mar 8, 2017
1 parent 1c7473c commit 8edc0f4
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions src/imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -228,8 +228,8 @@ static void calibrate_IMU(void){
gyro_bias[1] /= (int32_t) packet_count;
gyro_bias[2] /= (int32_t) packet_count;

if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) ACCEL_SENSITIVITY;} // Remove gravity from the z-axis accelerometer bias calculation
else {accel_bias[2] += (int32_t) ACCEL_SENSITIVITY;}
if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) 16384;} // Remove gravity from the z-axis accelerometer bias calculation
else {accel_bias[2] += (int32_t) 16384;}

// Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
Expand Down
4 changes: 2 additions & 2 deletions src/settings.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@
//#define IMU_ID 0x73 // Pawel's IMU

// IMU sensor sensitivities.
#define GYRO_SENSITIVITY 131 // = 131 LSB/degrees/sec
#define ACCEL_SENSITIVITY 16384 // = 16384 LSB/g
#define GYRO_SENSITIVITY 65.5 // = 65.5 LSB/degrees/sec
#define ACCEL_SENSITIVITY 4096 // = 4096 LSB/g (8g range)

// Allowable limits for rotor speeds (0.0 = 1ms pulse, 1.0 = 2ms pulse).
#define MIN_ROTOR_SPEED 0.0
Expand Down

0 comments on commit 8edc0f4

Please sign in to comment.