Skip to content

Commit

Permalink
Merge pull request #984 from PX4/rc_channels
Browse files Browse the repository at this point in the history
rc_channels cleanup
  • Loading branch information
LorenzMeier committed Jun 30, 2014
2 parents 68c8090 + e92620b commit 45016b0
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 58 deletions.
1 change: 0 additions & 1 deletion src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@

#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
Expand Down
4 changes: 2 additions & 2 deletions src/modules/sdlog2/sdlog2.c
Original file line number Diff line number Diff line change
Expand Up @@ -1394,8 +1394,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (copy_if_updated(ORB_ID(rc_channels), subs.rc_sub, &buf.rc)) {
log_msg.msg_type = LOG_RC_MSG;
/* Copy only the first 8 channels of 14 */
memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
log_msg.body.log_RC.channel_count = buf.rc.chan_count;
memcpy(log_msg.body.log_RC.channel, buf.rc.channels, sizeof(log_msg.body.log_RC.channel));
log_msg.body.log_RC.channel_count = buf.rc.channel_count;
log_msg.body.log_RC.signal_lost = buf.rc.signal_lost;
LOGBUFFER_WRITE_AND_COUNT(RC);
}
Expand Down
26 changes: 13 additions & 13 deletions src/modules/sensors/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1223,9 +1223,9 @@ Sensors::parameter_update_poll(bool forced)
}

#if 0
printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]);
printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]);
printf("MAN: %d %d\n", (int)(_rc.chan[0].scaled * 100), (int)(_rc.chan[1].scaled * 100));
printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.channels[0].scaling_factor * 10000), (int)(_rc.channels[0].mid), (int)_rc.function[0]);
printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.channels[1].scaling_factor * 10000), (int)(_rc.channels[1].mid), (int)_rc.function[1]);
printf("MAN: %d %d\n", (int)(_rc.channels[0] * 100), (int)(_rc.channels[1] * 100));
fflush(stdout);
usleep(5000);
#endif
Expand Down Expand Up @@ -1355,7 +1355,7 @@ float
Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max_value)
{
if (_rc.function[func] >= 0) {
float value = _rc.chan[_rc.function[func]].scaled;
float value = _rc.channels[_rc.function[func]];

if (value < min_value) {
return min_value;
Expand All @@ -1376,7 +1376,7 @@ switch_pos_t
Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv)
{
if (_rc.function[func] >= 0) {
float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
float value = 0.5f * _rc.channels[_rc.function[func]] + 0.5f;

if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
Expand All @@ -1397,7 +1397,7 @@ switch_pos_t
Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
{
if (_rc.function[func] >= 0) {
float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
float value = 0.5f * _rc.channels[_rc.function[func]] + 0.5f;

if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
Expand Down Expand Up @@ -1489,25 +1489,25 @@ Sensors::rc_poll()
* DO NOT REMOVE OR ALTER STEP 1!
*/
if (rc_input.values[i] > (_parameters.trim[i] + _parameters.dz[i])) {
_rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]);
_rc.channels[i] = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]);

} else if (rc_input.values[i] < (_parameters.trim[i] - _parameters.dz[i])) {
_rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] + _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]);
_rc.channels[i] = (rc_input.values[i] - _parameters.trim[i] + _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]);

} else {
/* in the configured dead zone, output zero */
_rc.chan[i].scaled = 0.0f;
_rc.channels[i] = 0.0f;
}

_rc.chan[i].scaled *= _parameters.rev[i];
_rc.channels[i] *= _parameters.rev[i];

/* handle any parameter-induced blowups */
if (!isfinite(_rc.chan[i].scaled)) {
_rc.chan[i].scaled = 0.0f;
if (!isfinite(_rc.channels[i])) {
_rc.channels[i] = 0.0f;
}
}

_rc.chan_count = rc_input.channel_count;
_rc.channel_count = rc_input.channel_count;
_rc.rssi = rc_input.rssi;
_rc.signal_lost = signal_lost;
_rc.timestamp = rc_input.timestamp_last_signal;
Expand Down
68 changes: 26 additions & 42 deletions src/modules/uORB/topics/rc_channels.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-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
Expand Down Expand Up @@ -42,60 +42,44 @@
#include <stdint.h>
#include "../uORB.h"

/**
* The number of RC channel inputs supported.
* Current (Q4/2013) radios support up to 18 channels,
* leaving at a sane value of 16.
* This number can be greater then number of RC channels,
* because single RC channel can be mapped to multiple
* functions, e.g. for various mode switches.
*/
#define RC_CHANNELS_MAPPED_MAX 16

/**
* This defines the mapping of the RC functions.
* The value assigned to the specific function corresponds to the entry of
* the channel array chan[].
* the channel array channels[].
*/
enum RC_CHANNELS_FUNCTION {
THROTTLE = 0,
ROLL = 1,
PITCH = 2,
YAW = 3,
MODE = 4,
RETURN = 5,
POSCTL = 6,
LOITER = 7,
OFFBOARD_MODE = 8,
ACRO = 9,
FLAPS = 10,
AUX_1 = 11,
AUX_2 = 12,
AUX_3 = 13,
AUX_4 = 14,
AUX_5 = 15,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
ROLL,
PITCH,
YAW,
MODE,
RETURN,
POSCTL,
LOITER,
OFFBOARD_MODE,
ACRO,
FLAPS,
AUX_1,
AUX_2,
AUX_3,
AUX_4,
AUX_5,
RC_CHANNELS_FUNCTION_MAX /**< Indicates the number of functions. There can be more functions than RC channels. */
};

/**
* @addtogroup topics
* @{
*/

struct rc_channels_s {

uint64_t timestamp; /**< In microseconds since boot time. */
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
struct {
float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
} chan[RC_CHANNELS_MAPPED_MAX];
uint8_t chan_count; /**< number of valid channels */

/*String array to store the names of the functions*/
char function_name[RC_CHANNELS_FUNCTION_MAX][20];
int8_t function[RC_CHANNELS_FUNCTION_MAX];
uint8_t rssi; /**< Overall receive signal strength */
bool signal_lost; /**< control signal lost, should be checked together with topic timeout */
uint64_t timestamp; /**< Timestamp in microseconds since boot time */
uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */
float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */
uint8_t channel_count; /**< Number of valid channels */
char function_name[RC_CHANNELS_FUNCTION_MAX][20]; /**< String array to store the names of the functions */
int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */
uint8_t rssi; /**< Receive signal strength index */
bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */
}; /**< radio control channels. */

/**
Expand Down

0 comments on commit 45016b0

Please sign in to comment.