mirror of https://github.com/ArduPilot/ardupilot
Rover: Convert PRX_ parameters to PRX1_
This commit is contained in:
parent
8fcd42d104
commit
0ec331dd16
|
@ -758,8 +758,22 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
|||
{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },
|
||||
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
|
||||
{ Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" },
|
||||
{ Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" },
|
||||
{ Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" },
|
||||
{ Parameters::k_param_g2, 210, AP_PARAM_INT16, "PRX1_YAW_CORR" },
|
||||
{ Parameters::k_param_g2, 274, AP_PARAM_INT16, "PRX1_IGN_ANG1" },
|
||||
{ Parameters::k_param_g2, 338, AP_PARAM_INT8, "PRX1_IGN_WID1" },
|
||||
{ Parameters::k_param_g2, 402, AP_PARAM_INT16, "PRX1_IGN_ANG2" },
|
||||
{ Parameters::k_param_g2, 466, AP_PARAM_INT8, "PRX1_IGN_WID2" },
|
||||
{ Parameters::k_param_g2, 530, AP_PARAM_INT16, "PRX1_IGN_ANG3" },
|
||||
{ Parameters::k_param_g2, 594, AP_PARAM_INT8, "PRX1_IGN_WID3" },
|
||||
{ Parameters::k_param_g2, 658, AP_PARAM_INT16, "PRX1_IGN_ANG4" },
|
||||
{ Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" },
|
||||
{ Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" },
|
||||
{ Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" },
|
||||
};
|
||||
|
||||
|
||||
void Rover::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
|
|
Loading…
Reference in New Issue