aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
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/mavlink
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/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_parameters.cpp41
-rw-r--r--src/modules/mavlink/mavlink_parameters.h5
2 files changed, 45 insertions, 1 deletions
diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp
index cd5f53d88..e9858b73c 100644
--- a/src/modules/mavlink/mavlink_parameters.cpp
+++ b/src/modules/mavlink/mavlink_parameters.cpp
@@ -44,7 +44,9 @@
#include "mavlink_main.h"
MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink),
- _send_all_index(-1)
+ _send_all_index(-1),
+ _rc_param_map_pub(-1),
+ _rc_param_map()
{
}
@@ -135,6 +137,43 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
break;
}
+ case MAVLINK_MSG_ID_PARAM_MAP_RC: {
+ /* map a rc channel to a parameter */
+ mavlink_param_map_rc_t map_rc;
+ mavlink_msg_param_map_rc_decode(msg, &map_rc);
+
+ if (map_rc.target_system == mavlink_system.sysid &&
+ (map_rc.target_component == mavlink_system.compid ||
+ map_rc.target_component == MAV_COMP_ID_ALL)) {
+
+ /* Copy values from msg to uorb using the parameter_rc_channel_index as index */
+ size_t i = map_rc.parameter_rc_channel_index;
+ _rc_param_map.param_index[i] = map_rc.param_index;
+ strncpy(&(_rc_param_map.param_id[i][0]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
+ /* enforce null termination */
+ _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 {
+ _rc_param_map.valid[i] = true;
+ }
+ _rc_param_map.timestamp = hrt_absolute_time();
+
+ if (_rc_param_map_pub < 0) {
+ _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map);
+
+ } else {
+ orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map);
+ }
+
+ }
+ break;
+ }
+
default:
break;
}
diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h
index 5576e6b84..b6736f212 100644
--- a/src/modules/mavlink/mavlink_parameters.h
+++ b/src/modules/mavlink/mavlink_parameters.h
@@ -44,6 +44,8 @@
#include "mavlink_bridge_header.h"
#include "mavlink_stream.h"
+#include <uORB/uORB.h>
+#include <uORB/topics/rc_parameter_map.h>
class MavlinkParametersManager : public MavlinkStream
{
@@ -112,4 +114,7 @@ protected:
void send(const hrt_abstime t);
void send_param(param_t param);
+
+ orb_advert_t _rc_param_map_pub;
+ struct rc_parameter_map_s _rc_param_map;
};