mirror of https://github.com/ArduPilot/ardupilot
Rover: update for new SRV_Channels parameter conversion call
This commit is contained in:
parent
1cbad0c86e
commit
72ddcb593b
|
@ -755,15 +755,7 @@ void Rover::load_parameters(void)
|
||||||
g2.crash_angle.set_default(30);
|
g2.crash_angle.set_default(30);
|
||||||
}
|
}
|
||||||
|
|
||||||
const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old,
|
SRV_Channels::upgrade_parameters();
|
||||||
Parameters::k_param_rc_3_old, Parameters::k_param_rc_4_old,
|
|
||||||
Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old,
|
|
||||||
Parameters::k_param_rc_7_old, Parameters::k_param_rc_8_old,
|
|
||||||
Parameters::k_param_rc_9_old, Parameters::k_param_rc_10_old,
|
|
||||||
Parameters::k_param_rc_11_old, Parameters::k_param_rc_12_old,
|
|
||||||
Parameters::k_param_rc_13_old, Parameters::k_param_rc_14_old };
|
|
||||||
const uint16_t old_aux_chan_mask = 0x3FFA;
|
|
||||||
SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, &rcmap);
|
|
||||||
hal.console->printf("load_all took %uus\n", unsigned(micros() - before));
|
hal.console->printf("load_all took %uus\n", unsigned(micros() - before));
|
||||||
|
|
||||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||||
|
|
Loading…
Reference in New Issue