mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 17:35:22 +08:00
Removed commented-out lines (EXP support)
This commit is contained in:
@@ -69,98 +69,84 @@ PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
|
||||
PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
|
||||
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC1_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC1_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC2_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC2_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC2_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC2_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC2_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC3_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC3_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC3_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC3_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC3_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC3_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC4_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC4_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC4_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC4_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC4_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC4_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC5_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC5_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC5_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC5_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC5_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC5_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC6_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC6_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC6_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC6_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC6_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC6_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC7_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC7_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC7_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC7_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC7_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC7_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC8_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC8_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC8_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC8_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC8_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC8_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC9_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC9_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC9_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC9_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC9_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC10_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC10_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC10_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC10_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC10_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC11_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC11_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC11_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC11_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC11_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC12_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC12_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC12_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC12_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC12_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC13_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC13_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC13_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC13_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC13_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(RC14_MIN, 1000);
|
||||
PARAM_DEFINE_FLOAT(RC14_TRIM, 1500);
|
||||
PARAM_DEFINE_FLOAT(RC14_MAX, 2000);
|
||||
PARAM_DEFINE_FLOAT(RC14_REV, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
|
||||
// PARAM_DEFINE_FLOAT(RC12_EXP, 0.0f);
|
||||
|
||||
PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
|
||||
|
||||
|
||||
@@ -417,15 +417,10 @@ Sensors::Sensors() :
|
||||
sprintf(nbuf, "RC%d_DZ", i + 1);
|
||||
_parameter_handles.dz[i] = param_find(nbuf);
|
||||
|
||||
// /* channel exponential gain */
|
||||
// sprintf(nbuf, "RC%d_EXP", i + 1);
|
||||
// _parameter_handles.ex[i] = param_find(nbuf);
|
||||
}
|
||||
|
||||
_parameter_handles.rc_type = param_find("RC_TYPE");
|
||||
|
||||
// _parameter_handles.rc_demix = param_find("RC_DEMIX");
|
||||
|
||||
/* mandatory input switched, mapped to channels 1-4 per default */
|
||||
_parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL");
|
||||
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
|
||||
@@ -530,9 +525,6 @@ Sensors::parameters_update()
|
||||
if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) {
|
||||
warnx("Failed getting dead zone for chan %d", i);
|
||||
}
|
||||
// if (param_get(_parameter_handles.ex[i], &(_parameters.ex[i])) != OK) {
|
||||
// warnx("Failed getting exponential gain for chan %d", i);
|
||||
// }
|
||||
|
||||
_parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user