mirror of https://github.com/ArduPilot/ardupilot
Sub: don't override default RNGFND1_TYPE
This is causing side-effects in QGC 4.1, as it reports the Range- finder to be in bad health, which causes qgc to show "not ready to fly" instead of "ready to fly" which might confuse users
This commit is contained in:
parent
5e3caefc2d
commit
e448910ff0
|
@ -726,7 +726,6 @@ void Sub::load_parameters()
|
|||
AP_Param::set_default_by_name("INS_GYR_CAL", 0);
|
||||
AP_Param::set_default_by_name("MNT_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING);
|
||||
AP_Param::set_default_by_name("MNT_JSTICK_SPD", 100);
|
||||
AP_Param::set_default_by_name("RNGFND1_TYPE", (uint8_t)RangeFinder::Type::MAVLink);
|
||||
AP_Param::set_by_name("MNT_RC_IN_PAN", 7);
|
||||
AP_Param::set_by_name("MNT_RC_IN_TILT", 8);
|
||||
// We should ignore this parameter since ROVs are neutral buoyancy
|
||||
|
|
Loading…
Reference in New Issue