Browse Source

Merge pull request #1543 from thomasgubler/rcparamtune

RC param tune
sbg
Lorenz Meier 10 years ago
parent
commit
a0e1255e28
  1. 2
      mavlink/include/mavlink/v1.0
  2. 41
      src/modules/mavlink/mavlink_parameters.cpp
  3. 5
      src/modules/mavlink/mavlink_parameters.h
  4. 35
      src/modules/sensors/sensor_params.c
  5. 118
      src/modules/sensors/sensors.cpp
  6. 3
      src/modules/uORB/objects_common.cpp
  7. 7
      src/modules/uORB/topics/rc_channels.h
  8. 76
      src/modules/uORB/topics/rc_parameter_map.h

2
mavlink/include/mavlink/v1.0

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit ad5e5a645dec152419264ad32221f7c113ea5c30
Subproject commit 42f1a37397335b3c4c96b0a41c73d85e80d54a60

41
src/modules/mavlink/mavlink_parameters.cpp

@ -44,7 +44,9 @@ @@ -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) @@ -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;
}

5
src/modules/mavlink/mavlink_parameters.h

@ -44,6 +44,8 @@ @@ -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: @@ -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;
};

35
src/modules/sensors/sensor_params.c

@ -766,6 +766,41 @@ PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */ @@ -766,6 +766,41 @@ PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
*/
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
/**
* Channel which changes a parameter
*
* Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.
* Set to 0 to deactivate *
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_PARAM1, 0);
/**
* Channel which changes a parameter
*
* Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.
* Set to 0 to deactivate *
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_PARAM2, 0);
/**
* Channel which changes a parameter
*
* Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.
* Set to 0 to deactivate *
*
* @min 0
* @max 18
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0);
/**
* Failsafe channel PWM threshold.

118
src/modules/sensors/sensors.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@ -83,6 +83,7 @@ @@ -83,6 +83,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/rc_parameter_map.h>
#define GYRO_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */
#define ACC_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */
@ -191,6 +192,14 @@ private: @@ -191,6 +192,14 @@ private:
switch_pos_t get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv);
switch_pos_t get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv);
/**
* Update paramters from RC channels if the functionality is activated and the
* input has changed since the last update
*
* @param
*/
void set_params_from_rc();
/**
* Gather and publish RC input data.
*/
@ -221,6 +230,7 @@ private: @@ -221,6 +230,7 @@ private:
int _diff_pres_sub; /**< raw differential pressure subscription */
int _vcontrol_mode_sub; /**< vehicle control mode subscription */
int _params_sub; /**< notification of parameter updates */
int _rc_parameter_map_sub; /**< rc parameter map subscription */
int _manual_control_sub; /**< notification of manual control updates */
orb_advert_t _sensor_pub; /**< combined sensor data topic */
@ -238,6 +248,7 @@ private: @@ -238,6 +248,7 @@ private:
struct baro_report _barometer; /**< barometer data */
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
struct rc_parameter_map_s _rc_parameter_map;
math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
@ -290,6 +301,8 @@ private: @@ -290,6 +301,8 @@ private:
int rc_map_aux4;
int rc_map_aux5;
int rc_map_param[RC_PARAM_MAP_NCHAN];
int32_t rc_fails_thr;
float rc_assist_th;
float rc_auto_th;
@ -350,6 +363,12 @@ private: @@ -350,6 +363,12 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
param_t rc_map_param[RC_PARAM_MAP_NCHAN];
param_t rc_param[RC_PARAM_MAP_NCHAN]; /**< param handles for the paramters which are bound
to a RC channel, equivalent float values in the
_parameters struct are not existing
because these parameters are never read. */
param_t rc_fails_thr;
param_t rc_assist_th;
param_t rc_auto_th;
@ -453,6 +472,11 @@ private: @@ -453,6 +472,11 @@ private:
*/
void parameter_update_poll(bool forced = false);
/**
* Check for changes in rc_parameter_map
*/
void rc_parameter_map_poll(bool forced = false);
/**
* Poll the ADC and update readings to suit.
*
@ -501,6 +525,7 @@ Sensors::Sensors() : @@ -501,6 +525,7 @@ Sensors::Sensors() :
_baro_sub(-1),
_vcontrol_mode_sub(-1),
_params_sub(-1),
_rc_parameter_map_sub(-1),
_manual_control_sub(-1),
/* publications */
@ -521,6 +546,7 @@ Sensors::Sensors() : @@ -521,6 +546,7 @@ Sensors::Sensors() :
{
memset(&_rc, 0, sizeof(_rc));
memset(&_diff_pres, 0, sizeof(_diff_pres));
memset(&_rc_parameter_map, 0, sizeof(_rc_parameter_map));
/* basic r/c parameters */
for (unsigned i = 0; i < _rc_max_chan_count; i++) {
@ -573,6 +599,13 @@ Sensors::Sensors() : @@ -573,6 +599,13 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
/* RC to parameter mapping for changing parameters with RC */
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
char name[PARAM_ID_LEN];
snprintf(name, PARAM_ID_LEN, "RC_MAP_PARAM%d", i + 1); // shifted by 1 because param name starts at 1
_parameter_handles.rc_map_param[i] = param_find(name);
}
/* RC thresholds */
_parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
_parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
@ -751,6 +784,9 @@ Sensors::parameters_update() @@ -751,6 +784,9 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
param_get(_parameter_handles.rc_map_param[i], &(_parameters.rc_map_param[i]));
}
param_get(_parameter_handles.rc_fails_thr, &(_parameters.rc_fails_thr));
param_get(_parameter_handles.rc_assist_th, &(_parameters.rc_assist_th));
_parameters.rc_assist_inv = (_parameters.rc_assist_th < 0);
@ -795,6 +831,10 @@ Sensors::parameters_update() @@ -795,6 +831,10 @@ Sensors::parameters_update()
_rc.function[AUX_4] = _parameters.rc_map_aux4 - 1;
_rc.function[AUX_5] = _parameters.rc_map_aux5 - 1;
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
_rc.function[PARAM_1 + i] = _parameters.rc_map_param[i] - 1;
}
/* gyro offsets */
param_get(_parameter_handles.gyro_offset[0], &(_parameters.gyro_offset[0]));
param_get(_parameter_handles.gyro_offset[1], &(_parameters.gyro_offset[1]));
@ -1391,6 +1431,45 @@ Sensors::parameter_update_poll(bool forced) @@ -1391,6 +1431,45 @@ Sensors::parameter_update_poll(bool forced)
}
}
void
Sensors::rc_parameter_map_poll(bool forced)
{
bool map_updated;
orb_check(_rc_parameter_map_sub, &map_updated);
if (map_updated) {
orb_copy(ORB_ID(rc_parameter_map), _rc_parameter_map_sub, &_rc_parameter_map);
/* update paramter handles to which the RC channels are mapped */
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
if (_rc.function[PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
/* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
* or no request to map this channel to a param has been sent via mavlink
*/
continue;
}
/* Set the handle by index if the index is set, otherwise use the id */
if (_rc_parameter_map.param_index[i] >= 0) {
_parameter_handles.rc_param[i] = param_for_index((unsigned)_rc_parameter_map.param_index[i]);
} else {
_parameter_handles.rc_param[i] = param_find(_rc_parameter_map.param_id[i]);
}
}
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, 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.value_min[i],
(double)_rc_parameter_map.value_max[i]
);
}
}
}
void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
@ -1569,6 +1648,31 @@ Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, boo @@ -1569,6 +1648,31 @@ Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, boo
}
}
void
Sensors::set_params_from_rc()
{
static float param_rc_values[RC_PARAM_MAP_NCHAN] = {};
for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
if (_rc.function[PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
/* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
* or no request to map this channel to a param has been sent via mavlink
*/
continue;
}
float rc_val = get_rc_value((enum RC_CHANNELS_FUNCTION)(PARAM_1 + i), -1.0, 1.0);
/* Check if the value has changed,
* 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 = 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);
}
}
}
void
Sensors::rc_poll()
{
@ -1735,6 +1839,13 @@ Sensors::rc_poll() @@ -1735,6 +1839,13 @@ Sensors::rc_poll()
} else {
_actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3);
}
/* Update parameters from RC Channels (tuning with RC) if activated */
static hrt_abstime last_rc_to_param_map_time = 0;
if (hrt_elapsed_time(&last_rc_to_param_map_time) > 1e6) {
set_params_from_rc();
last_rc_to_param_map_time = hrt_absolute_time();
}
}
}
}
@ -1773,6 +1884,7 @@ Sensors::task_main() @@ -1773,6 +1884,7 @@ Sensors::task_main()
_diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_rc_parameter_map_sub = orb_subscribe(ORB_ID(rc_parameter_map));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
/* rate limit vehicle status updates to 5Hz */
@ -1806,6 +1918,7 @@ Sensors::task_main() @@ -1806,6 +1918,7 @@ Sensors::task_main()
diff_pres_poll(raw);
parameter_update_poll(true /* forced */);
rc_parameter_map_poll(true /* forced */);
/* advertise the sensor_combined topic and make the initial publication */
_sensor_pub = orb_advertise(ORB_ID(sensor_combined), &raw);
@ -1838,6 +1951,9 @@ Sensors::task_main() @@ -1838,6 +1951,9 @@ Sensors::task_main()
/* check parameters for updates */
parameter_update_poll();
/* check rc parameter map for updates */
rc_parameter_map_poll();
/* the timestamp of the raw struct is updated by the gyro_poll() method */
/* copy most recent sensor data */

3
src/modules/uORB/objects_common.cpp

@ -246,3 +246,6 @@ ORB_DEFINE(tecs_status, struct tecs_status_s); @@ -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);

7
src/modules/uORB/topics/rc_channels.h

@ -65,12 +65,15 @@ enum RC_CHANNELS_FUNCTION { @@ -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

76
src/modules/uORB/topics/rc_parameter_map.h

@ -0,0 +1,76 @@ @@ -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
Loading…
Cancel
Save