aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
authorLorenz Meier <lorenz@px4.io>2015-01-01 18:15:28 +0100
committerLorenz Meier <lorenz@px4.io>2015-01-01 18:15:28 +0100
commita0e1255e288275ccfc50b33d4f10e539c4f6862f (patch)
tree5f1f590f6d4e95d99323a0f873874e6a93d1137a /src/modules/uORB
parenta7bc38869e2121b7f63e63e0fae4bfe4117a3315 (diff)
parentdd8dfc971cb459dbdc849a0f320431516625bfee (diff)
downloadpx4-firmware-a0e1255e288275ccfc50b33d4f10e539c4f6862f.tar.gz
px4-firmware-a0e1255e288275ccfc50b33d4f10e539c4f6862f.tar.bz2
px4-firmware-a0e1255e288275ccfc50b33d4f10e539c4f6862f.zip
Merge pull request #1543 from thomasgubler/rcparamtune
RC param tune
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/objects_common.cpp3
-rw-r--r--src/modules/uORB/topics/rc_channels.h7
-rw-r--r--src/modules/uORB/topics/rc_parameter_map.h76
3 files changed, 84 insertions, 2 deletions
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 3d5755a46..d834c3574 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -246,3 +246,6 @@ ORB_DEFINE(tecs_status, struct tecs_status_s);
#include "topics/wind_estimate.h"
ORB_DEFINE(wind_estimate, struct wind_estimate_s);
+
+#include "topics/rc_parameter_map.h"
+ORB_DEFINE(rc_parameter_map, struct rc_parameter_map_s);
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 16916cc4d..2fde5d424 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -65,12 +65,15 @@ enum RC_CHANNELS_FUNCTION {
AUX_2,
AUX_3,
AUX_4,
- AUX_5
+ AUX_5,
+ PARAM_1,
+ PARAM_2,
+ PARAM_3
};
// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS
-#define RC_CHANNELS_FUNCTION_MAX 18
+#define RC_CHANNELS_FUNCTION_MAX 19
/**
* @addtogroup topics
diff --git a/src/modules/uORB/topics/rc_parameter_map.h b/src/modules/uORB/topics/rc_parameter_map.h
new file mode 100644
index 000000000..6e68dc4b6
--- /dev/null
+++ b/src/modules/uORB/topics/rc_parameter_map.h
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT ,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_parameter_map.h
+ * Maps RC channels to parameters
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef TOPIC_RC_PARAMETER_MAP_H
+#define TOPIC_RC_PARAMETER_MAP_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define RC_PARAM_MAP_NCHAN 3 // This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h
+#define PARAM_ID_LEN 16 // corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct rc_parameter_map_s {
+ uint64_t timestamp; /**< time at which the map was updated */
+
+ bool valid[RC_PARAM_MAP_NCHAN]; /**< true for RC-Param channels which are mapped to a param */
+
+ int param_index[RC_PARAM_MAP_NCHAN]; /**< corresponding param index, this
+ this field is ignored if set to -1, in this case param_id will
+ be used*/
+ 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 */
+};
+
+/**
+ * @}
+ */
+
+ORB_DECLARE(rc_parameter_map);
+
+#endif