rc2param: min and max values

This commit is contained in:
Thomas Gubler 2014-12-28 21:57:30 +01:00
parent e9b41528dc
commit ef8abfbf14
4 changed files with 12 additions and 4 deletions

@ -1 +1 @@
Subproject commit 87350ba3d2e42d15c5934fe3c3387167e9f8769f
Subproject commit b5732d07ec89025a9d321a923fe027d7df7b30a6

View File

@ -154,6 +154,8 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
_rc_param_map.param_id[i][MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = '\0';
_rc_param_map.scale[i] = map_rc.scale;
_rc_param_map.value0[i] = map_rc.param_value0;
_rc_param_map.value_min[i] = map_rc.param_value_min;
_rc_param_map.value_max[i] = map_rc.param_value_max;
if (map_rc.param_index == -2) { // -2 means unset map
_rc_param_map.valid[i] = false;
} else {

View File

@ -1440,11 +1440,13 @@ Sensors::rc_parameter_map_poll(bool forced)
}
warnx("rc to parameter map updated");
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
warnx("\ti %d param_id %s scale %.3f value0 %.3f",
warnx("\ti %d param_id %s scale %.3f value0 %.3f, min %.3f, max %.3f",
i,
_rc_parameter_map.param_id[i],
(double)_rc_parameter_map.scale[i],
(double)_rc_parameter_map.value0[i]
(double)_rc_parameter_map.value0[i],
(double)_rc_parameter_map.value_min[i],
(double)_rc_parameter_map.value_max[i]
);
}
}
@ -1645,7 +1647,9 @@ Sensors::set_params_from_rc()
* maybe we need to introduce a more aggressive limit here */
if (rc_val > param_rc_values[i] + FLT_EPSILON || rc_val < param_rc_values[i] - FLT_EPSILON) {
param_rc_values[i] = rc_val;
float param_val = _rc_parameter_map.value0[i] + _rc_parameter_map.scale[i] * rc_val;
float param_val = math::constrain(
_rc_parameter_map.value0[i] + _rc_parameter_map.scale[i] * rc_val,
_rc_parameter_map.value_min[i], _rc_parameter_map.value_max[i]);
param_set(_parameter_handles.rc_param[i], &param_val);
}
}

View File

@ -63,6 +63,8 @@ struct rc_parameter_map_s {
char param_id[RC_PARAM_MAP_NCHAN][PARAM_ID_LEN + 1]; /**< corresponding param id, null terminated */
float scale[RC_PARAM_MAP_NCHAN]; /** scale to map the RC input [-1, 1] to a parameter value */
float value0[RC_PARAM_MAP_NCHAN]; /** inital value around which the parameter value is changed */
float value_min[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
float value_max[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
};
/**