mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_BoardConfig: set default temperature on PH2 to 60
This commit is contained in:
parent
7806aa4274
commit
7c5171e9b9
@ -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…
Reference in New Issue
Block a user