From ef8abfbf148ac6fd7a405acdd4ee8eeb156867b6 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 28 Dec 2014 21:57:30 +0100 Subject: rc2param: min and max values --- src/modules/uORB/topics/rc_parameter_map.h | 2 ++ 1 file changed, 2 insertions(+) (limited to 'src/modules/uORB') diff --git a/src/modules/uORB/topics/rc_parameter_map.h b/src/modules/uORB/topics/rc_parameter_map.h index 47672c5d5..6e68dc4b6 100644 --- a/src/modules/uORB/topics/rc_parameter_map.h +++ b/src/modules/uORB/topics/rc_parameter_map.h @@ -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 */ }; /** -- cgit v1.2.3