mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: fix long booting
This commit is contained in:
parent
ec2d5d0756
commit
ca0ae1d9c6
@ -870,10 +870,7 @@ void Rover::load_parameters(void)
|
|||||||
{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },
|
{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },
|
||||||
{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },
|
{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },
|
||||||
};
|
};
|
||||||
uint8_t filt_table_size = ARRAY_SIZE(ff_and_filt_conversion_info);
|
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[0], ARRAY_SIZE(ff_and_filt_conversion_info));
|
||||||
for (uint8_t i=0; i<filt_table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[i], 1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
// configure safety switch to allow stopping the motors while armed
|
// configure safety switch to allow stopping the motors while armed
|
||||||
#if HAL_HAVE_SAFETY_SWITCH
|
#if HAL_HAVE_SAFETY_SWITCH
|
||||||
|
Loading…
Reference in New Issue
Block a user