2010-11-28 03:03:23 -04:00
|
|
|
/// @file RC_Channel.h
|
|
|
|
/// @brief RC_Channel manager, with EEPROM-backed storage of constants.
|
2016-02-17 21:25:57 -04:00
|
|
|
#pragma once
|
2010-11-23 15:28:19 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2012-10-26 20:59:16 -03:00
|
|
|
|
2012-12-09 03:42:58 -04:00
|
|
|
#define RC_CHANNEL_TYPE_ANGLE 0
|
|
|
|
#define RC_CHANNEL_TYPE_RANGE 1
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
#define NUM_RC_CHANNELS 16
|
2013-08-17 22:37:42 -03:00
|
|
|
|
2010-11-28 03:03:23 -04:00
|
|
|
/// @class RC_Channel
|
|
|
|
/// @brief Object managing one RC channel
|
2012-08-17 03:22:48 -03:00
|
|
|
class RC_Channel {
|
|
|
|
public:
|
2017-01-08 20:47:26 -04:00
|
|
|
friend class SRV_Channels;
|
2016-10-22 07:27:40 -03:00
|
|
|
friend class RC_Channels;
|
|
|
|
// Constructor
|
|
|
|
RC_Channel(void);
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2014-04-20 21:34:10 -03:00
|
|
|
// used to get min/max/trim limit value based on _reverse
|
|
|
|
enum LimitValue {
|
|
|
|
RC_CHANNEL_LIMIT_TRIM,
|
|
|
|
RC_CHANNEL_LIMIT_MIN,
|
|
|
|
RC_CHANNEL_LIMIT_MAX
|
|
|
|
};
|
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
// setup the control preferences
|
2016-10-22 07:27:40 -03:00
|
|
|
void set_range(uint16_t high);
|
|
|
|
void set_angle(uint16_t angle);
|
2014-04-20 21:34:10 -03:00
|
|
|
bool get_reverse(void) const;
|
2013-07-11 11:08:16 -03:00
|
|
|
void set_default_dead_zone(int16_t dzone);
|
2016-10-22 07:27:40 -03:00
|
|
|
uint16_t get_dead_zone(void) const { return dead_zone; }
|
2014-04-20 21:34:10 -03:00
|
|
|
|
2014-11-17 18:00:31 -04:00
|
|
|
// get the center stick position expressed as a control_in value
|
2014-11-17 20:18:51 -04:00
|
|
|
int16_t get_control_mid() const;
|
2014-11-17 18:00:31 -04:00
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// read input from hal.rcin - create a control_in value
|
2012-08-17 03:22:48 -03:00
|
|
|
void set_pwm(int16_t pwm);
|
2018-04-10 19:50:16 -03:00
|
|
|
void recompute_pwm_no_deadzone();
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// calculate an angle given dead_zone and trim. This is used by the quadplane code
|
|
|
|
// for hover throttle
|
2016-05-08 05:22:32 -03:00
|
|
|
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim);
|
2014-11-17 21:44:05 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a normalised input for a channel, in range -1 to 1,
|
|
|
|
centered around the channel trim. Ignore deadzone.
|
|
|
|
*/
|
2016-05-08 05:22:32 -03:00
|
|
|
float norm_input();
|
2014-11-17 21:44:05 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a normalised input for a channel, in range -1 to 1,
|
|
|
|
centered around the channel trim. Take into account the deadzone
|
|
|
|
*/
|
2016-05-08 05:22:32 -03:00
|
|
|
float norm_input_dz();
|
|
|
|
|
|
|
|
uint8_t percent_input();
|
|
|
|
int16_t pwm_to_range();
|
|
|
|
int16_t pwm_to_range_dz(uint16_t dead_zone);
|
2017-01-07 01:37:00 -04:00
|
|
|
|
|
|
|
// read the input value from hal.rcin for this channel
|
2016-05-08 05:22:32 -03:00
|
|
|
uint16_t read() const;
|
2017-01-07 01:37:00 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
// return true if input is within deadzone of trim
|
2016-10-22 07:27:40 -03:00
|
|
|
bool in_trim_dz();
|
|
|
|
|
|
|
|
int16_t get_radio_in() const { return radio_in;}
|
|
|
|
void set_radio_in(int16_t val) {radio_in = val;}
|
|
|
|
|
|
|
|
int16_t get_control_in() const { return control_in;}
|
|
|
|
void set_control_in(int16_t val) { control_in = val;}
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
void clear_override();
|
|
|
|
void set_override(const uint16_t v, const uint32_t timestamp_us=0);
|
|
|
|
bool has_override() const;
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// get control input with zero deadzone
|
|
|
|
int16_t get_control_in_zero_dz(void);
|
|
|
|
|
|
|
|
int16_t get_radio_min() const {return radio_min.get();}
|
|
|
|
void set_radio_min(int16_t val) { radio_min = val;}
|
|
|
|
|
|
|
|
int16_t get_radio_max() const {return radio_max.get();}
|
|
|
|
void set_radio_max(int16_t val) {radio_max = val;}
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t get_radio_trim() const { return radio_trim.get();}
|
|
|
|
void set_radio_trim(int16_t val) { radio_trim.set(val);}
|
|
|
|
void save_radio_trim() { radio_trim.save();}
|
2013-06-03 02:11:17 -03:00
|
|
|
|
2017-07-01 19:46:06 -03:00
|
|
|
void set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);}
|
2018-01-05 21:51:04 -04:00
|
|
|
|
|
|
|
// set and save trim if changed
|
|
|
|
void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
|
2017-07-01 07:04:44 -03:00
|
|
|
|
2018-01-08 23:41:02 -04:00
|
|
|
bool min_max_configured() const;
|
2016-03-25 07:35:33 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
private:
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// pwm is stored here
|
|
|
|
int16_t radio_in;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// value generated from PWM normalised to configured scale
|
|
|
|
int16_t control_in;
|
|
|
|
|
|
|
|
AP_Int16 radio_min;
|
|
|
|
AP_Int16 radio_trim;
|
|
|
|
AP_Int16 radio_max;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_Int8 reversed;
|
|
|
|
AP_Int16 dead_zone;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
uint8_t type_in;
|
|
|
|
int16_t high_in;
|
2015-10-30 02:46:03 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// the input channel this corresponds to
|
|
|
|
uint8_t ch_in;
|
2016-05-08 05:22:32 -03:00
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
// overrides
|
|
|
|
uint16_t override_value;
|
|
|
|
uint32_t last_override_time;
|
|
|
|
|
2018-01-08 23:41:02 -04:00
|
|
|
// bits set when channel has been identified as configured
|
|
|
|
static uint32_t configured_mask;
|
|
|
|
|
2017-01-07 01:37:00 -04:00
|
|
|
int16_t pwm_to_angle();
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t pwm_to_angle_dz(uint16_t dead_zone);
|
|
|
|
};
|
2016-05-08 05:22:32 -03:00
|
|
|
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
/*
|
|
|
|
class RC_Channels. Hold the full set of RC_Channel objects
|
|
|
|
*/
|
|
|
|
class RC_Channels {
|
|
|
|
public:
|
2017-01-08 20:47:26 -04:00
|
|
|
friend class SRV_Channels;
|
2018-04-25 23:06:19 -03:00
|
|
|
friend class RC_Channel;
|
2016-10-22 07:27:40 -03:00
|
|
|
// constructor
|
|
|
|
RC_Channels(void);
|
2016-10-11 08:00:48 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
static RC_Channel *rc_channel(uint8_t chan) {
|
|
|
|
return (chan < NUM_RC_CHANNELS)?&channels[chan]:nullptr;
|
2016-05-08 05:22:32 -03:00
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
|
2018-04-03 23:16:36 -03:00
|
|
|
static uint16_t get_radio_in(const uint8_t chan); // returns the last read radio_in value from a chan, 0 if the channel is out of range
|
|
|
|
static uint8_t get_radio_in(uint16_t *chans, const uint8_t num_channels); // reads a block of chanel radio_in values starting from channel 0
|
|
|
|
// returns the number of valid channels
|
|
|
|
|
|
|
|
static uint8_t get_valid_channel_count(void); // returns the number of valid channels in the last read
|
|
|
|
static int16_t get_receiver_rssi(void); // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1
|
2018-04-24 01:20:02 -03:00
|
|
|
static bool read_input(void); // returns true if new input has been read in
|
2018-04-03 23:16:36 -03:00
|
|
|
static void clear_overrides(void); // clears any active overrides
|
|
|
|
static bool receiver_bind(const int dsmMode); // puts the reciever in bind mode if present, returns true if success
|
2018-04-25 23:06:19 -03:00
|
|
|
static void set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms = 0); // set a channels override value
|
|
|
|
static bool has_active_overrides(void); // returns true if there are overrides applied that are valid
|
2018-04-03 23:16:36 -03:00
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
private:
|
2016-10-22 07:27:40 -03:00
|
|
|
// this static arrangement is to avoid static pointers in AP_Param tables
|
|
|
|
static RC_Channel *channels;
|
2018-04-25 23:06:19 -03:00
|
|
|
static bool has_new_overrides;
|
|
|
|
static AP_Float *override_timeout;
|
2016-10-22 07:27:40 -03:00
|
|
|
RC_Channel obj_channels[NUM_RC_CHANNELS];
|
2018-04-25 23:06:19 -03:00
|
|
|
AP_Float _override_timeout;
|
2010-11-23 15:28:19 -04:00
|
|
|
};
|