Browse Source

AP_BoardConfig: drop target temperature for cube to 45

getting to 60 was taking far too long (15 minutes or so). 45 is more
achievable.

This is a result of the fix to the invensense temperature detection
code
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
a3cb6a42c9
  1. 4
      libraries/AP_BoardConfig/px4_drivers.cpp

4
libraries/AP_BoardConfig/px4_drivers.cpp

@ -299,11 +299,11 @@ void AP_BoardConfig::px4_setup_drivers(void) @@ -299,11 +299,11 @@ void AP_BoardConfig::px4_setup_drivers(void)
if (px4.board_type == PX4_BOARD_PH2SLIM ||
px4.board_type == PX4_BOARD_PIXHAWK2) {
_imu_target_temperature.set_default(60);
_imu_target_temperature.set_default(45);
if (_imu_target_temperature.get() < 0) {
// don't allow a value of -1 on the cube, or it could cook
// the IMU
_imu_target_temperature.set(60);
_imu_target_temperature.set(45);
}
}

Loading…
Cancel
Save