Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_InertialSensor: Clearly state the maximum G-force #27424

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ bool AP_InertialSensor_ADIS1647x::check_product_id(uint16_t &prod_id)
// can do up to 40G
opmode = OpMode::Basic;
accel_scale = 1.25 * GRAVITY_MSS * 0.001;
_clip_limit = 39.5f * GRAVITY_MSS;
_clip_limit = (40.0f - 0.5f) * GRAVITY_MSS;
gyro_scale = radians(0.1);
expected_sample_rate_hz = 2000;
return true;
Expand All @@ -146,7 +146,7 @@ bool AP_InertialSensor_ADIS1647x::check_product_id(uint16_t &prod_id)
// can do up to 40G
opmode = OpMode::Basic;
accel_scale = 1.25 * GRAVITY_MSS * 0.001;
_clip_limit = 39.5f * GRAVITY_MSS;
_clip_limit = (40.0f - 0.5f) * GRAVITY_MSS;
expected_sample_rate_hz = 2000;
// RANG_MDL register used for gyro range
uint16_t rang_mdl = read_reg16(REG_RANG_MDL);
Expand All @@ -167,11 +167,12 @@ bool AP_InertialSensor_ADIS1647x::check_product_id(uint16_t &prod_id)
}

case PROD_ID_16507: {
// can do up to 40G
opmode = OpMode::Delta32;
expected_sample_rate_hz = 1200;
accel_scale = 392.0 / 2097152000.0;
dvel_scale = 400.0 / 0x7FFFFFFF;
_clip_limit = 39.5f * GRAVITY_MSS;
_clip_limit = (40.0f - 0.5f) * GRAVITY_MSS;
// RANG_MDL register used for gyro range
uint16_t rang_mdl = read_reg16(REG_RANG_MDL);
switch ((rang_mdl >> 2) & 3) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ class AP_InertialSensor_Backend
HAL_Semaphore _sem;

//Default Clip Limit
float _clip_limit = 15.5f * GRAVITY_MSS;
float _clip_limit = (16.0f - 0.5f) * GRAVITY_MSS;

// instance numbers of accel and gyro data
uint8_t gyro_instance;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1037,7 +1037,7 @@ bool AP_InertialSensor_Invensensev3::hardware_init(void)
case Invensensev3_Type::ICM42605:
case Invensensev3_Type::ICM40605:
case Invensensev3_Type::ICM42670:
_clip_limit = 15.5f * GRAVITY_MSS;
_clip_limit = (16.0f - 0.5f) * GRAVITY_MSS;
break;
}

Expand Down
Loading