mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Copter: Change STAB_COL params to percent
This commit is contained in:
parent
78376e45a5
commit
5131431d23
@ -191,6 +191,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Heli motors checks failed");
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Heli motors checks failed");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
char fail_msg[50];
|
||||||
|
// check input mangager parameters
|
||||||
|
if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {
|
||||||
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "%s", fail_msg);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// Inverted flight feature disabled for Heli Single and Dual frames
|
// Inverted flight feature disabled for Heli Single and Dual frames
|
||||||
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
|
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
|
||||||
rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) {
|
rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) {
|
||||||
|
@ -1548,6 +1548,20 @@ void Copter::convert_tradheli_parameters(void)
|
|||||||
AP_Param::set_and_save_by_name("H_TAIL_SPEED", tailspeed_pct );
|
AP_Param::set_and_save_by_name("H_TAIL_SPEED", tailspeed_pct );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// table of stabilize collective parameters to be converted with scaling
|
||||||
|
const AP_Param::ConversionInfo collhelipct_conversion_info[] = {
|
||||||
|
{ Parameters::k_param_input_manager, 1, AP_PARAM_INT16, "IM_STB_COL_1" },
|
||||||
|
{ Parameters::k_param_input_manager, 2, AP_PARAM_INT16, "IM_STB_COL_2" },
|
||||||
|
{ Parameters::k_param_input_manager, 3, AP_PARAM_INT16, "IM_STB_COL_3" },
|
||||||
|
{ Parameters::k_param_input_manager, 4, AP_PARAM_INT16, "IM_STB_COL_4" },
|
||||||
|
};
|
||||||
|
|
||||||
|
// convert stabilize collective parameters with scaling
|
||||||
|
table_size = ARRAY_SIZE(collhelipct_conversion_info);
|
||||||
|
for (uint8_t i=0; i<table_size; i++) {
|
||||||
|
AP_Param::convert_old_parameter(&collhelipct_conversion_info[i], 0.1f);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user