mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: resetting the BRD_HEAT_TARG to 45 is not needed anymore
As iomcu fw has right default polarity now.
This commit is contained in:
parent
7db0c387cc
commit
ef8ebd85dd
|
@ -198,7 +198,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
|||
#if HAL_HAVE_IMU_HEATER
|
||||
// @Param: HEAT_TARG
|
||||
// @DisplayName: Board heater temperature target
|
||||
// @Description: Board heater target temperature for boards with controllable heating units. DO NOT SET to -1 on the Cube. Set to -1 to disable the heater, please reboot after setting to -1.
|
||||
// @Description: Board heater target temperature for boards with controllable heating units. Set to -1 to disable the heater, please reboot after setting to -1.
|
||||
// @Range: -1 80
|
||||
// @Units: degC
|
||||
// @User: Advanced
|
||||
|
|
|
@ -81,18 +81,6 @@ void AP_BoardConfig::board_setup_drivers(void)
|
|||
// run board auto-detection
|
||||
board_autodetect();
|
||||
|
||||
#if HAL_HAVE_IMU_HEATER
|
||||
if (state.board_type == PX4_BOARD_PH2SLIM ||
|
||||
state.board_type == PX4_BOARD_PIXHAWK2) {
|
||||
heater.imu_target_temperature.set_default(45);
|
||||
if (heater.imu_target_temperature.get() < 0) {
|
||||
// don't allow a value of -1 on the cube, or it could cook
|
||||
// the IMU
|
||||
heater.imu_target_temperature.set(45);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
px4_configured_board = (enum px4_board_type)state.board_type.get();
|
||||
|
||||
switch (px4_configured_board) {
|
||||
|
|
Loading…
Reference in New Issue