From 6ce42a429ba6e497e53dff450dd5d6319b75e7cd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 22 May 2017 12:19:38 +1000 Subject: [PATCH] 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 --- libraries/AP_BoardConfig/px4_drivers.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BoardConfig/px4_drivers.cpp b/libraries/AP_BoardConfig/px4_drivers.cpp index bb7629d870..f52654bb7e 100644 --- a/libraries/AP_BoardConfig/px4_drivers.cpp +++ b/libraries/AP_BoardConfig/px4_drivers.cpp @@ -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); } }