Browse Source

AP_BoardConfig: set default temperature on PH2 to 60

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
7c5171e9b9
  1. 6
      libraries/AP_BoardConfig/px4_drivers.cpp

6
libraries/AP_BoardConfig/px4_drivers.cpp

@ -338,6 +338,12 @@ void AP_BoardConfig::px4_start_fmuv2_sensors(void) @@ -338,6 +338,12 @@ void AP_BoardConfig::px4_start_fmuv2_sensors(void)
px4_sensor_error("no lsm303d found");
}
}
if (have_FMUV3) {
// on Pixhawk2 default IMU temperature to 60
_imu_target_temperature.set_default(60);
}
printf("FMUv2 sensors started\n");
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}

Loading…
Cancel
Save