2017-02-05 22:15:33 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* RC_Channels.cpp - class containing an array of RC_Channel objects
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <cmath>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
|
|
|
|
#include "RC_Channel.h"
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
bool RC_Channels::has_new_overrides;
|
|
|
|
AP_Float *RC_Channels::override_timeout;
|
2018-07-24 22:50:01 -03:00
|
|
|
AP_Int32 *RC_Channels::options;
|
2017-02-05 22:15:33 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
channels group object constructor
|
|
|
|
*/
|
|
|
|
RC_Channels::RC_Channels(void)
|
|
|
|
{
|
2018-04-25 23:06:19 -03:00
|
|
|
override_timeout = &_override_timeout;
|
2018-07-24 22:50:01 -03:00
|
|
|
options = &_options;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2017-02-05 22:15:33 -04:00
|
|
|
// set defaults from the parameter table
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
if (_singleton != nullptr) {
|
|
|
|
AP_HAL::panic("RC_Channels must be singleton");
|
2017-02-05 22:15:33 -04:00
|
|
|
}
|
2018-04-13 23:22:14 -03:00
|
|
|
_singleton = this;
|
2017-02-05 22:15:33 -04:00
|
|
|
}
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
void RC_Channels::init(void)
|
2018-04-03 23:16:36 -03:00
|
|
|
{
|
2018-04-13 23:22:14 -03:00
|
|
|
// setup ch_in on channels
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
channel(i)->ch_in = i;
|
2018-04-03 23:16:36 -03:00
|
|
|
}
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
init_aux_all();
|
2018-04-03 23:16:36 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
|
|
|
|
{
|
2018-08-06 18:52:19 -03:00
|
|
|
memset(chans, 0, num_channels*sizeof(*chans));
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
const uint8_t read_channels = MIN(num_channels, NUM_RC_CHANNELS);
|
2018-04-03 23:16:36 -03:00
|
|
|
for (uint8_t i = 0; i < read_channels; i++) {
|
2018-04-13 23:22:14 -03:00
|
|
|
chans[i] = channel(i)->get_radio_in();
|
2018-04-03 23:16:36 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return read_channels;
|
|
|
|
}
|
|
|
|
|
2018-07-24 22:50:01 -03:00
|
|
|
// update all the input channels
|
2018-04-13 23:22:14 -03:00
|
|
|
bool RC_Channels::read_input(void)
|
2017-02-05 22:15:33 -04:00
|
|
|
{
|
2018-04-25 23:06:19 -03:00
|
|
|
if (!hal.rcin->new_input() && !has_new_overrides) {
|
2018-04-24 01:20:02 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
has_new_overrides = false;
|
|
|
|
|
2018-07-24 22:50:01 -03:00
|
|
|
bool success = false;
|
2017-02-05 22:15:33 -04:00
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
2018-04-13 23:22:14 -03:00
|
|
|
success |= channel(i)->update();
|
2017-02-05 22:15:33 -04:00
|
|
|
}
|
2018-04-24 01:20:02 -03:00
|
|
|
|
2018-07-24 22:50:01 -03:00
|
|
|
return success;
|
2017-02-05 22:15:33 -04:00
|
|
|
}
|
2018-04-03 23:16:36 -03:00
|
|
|
|
|
|
|
uint8_t RC_Channels::get_valid_channel_count(void)
|
|
|
|
{
|
|
|
|
return MIN(NUM_RC_CHANNELS, hal.rcin->num_channels());
|
|
|
|
}
|
|
|
|
|
|
|
|
int16_t RC_Channels::get_receiver_rssi(void)
|
|
|
|
{
|
|
|
|
return hal.rcin->get_rssi();
|
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channels::clear_overrides(void)
|
|
|
|
{
|
2018-08-02 08:41:07 -03:00
|
|
|
RC_Channels &_rc = rc();
|
2018-04-25 23:06:19 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
2018-08-02 08:41:07 -03:00
|
|
|
_rc.channel(i)->clear_override();
|
2018-04-25 23:06:19 -03:00
|
|
|
}
|
|
|
|
// we really should set has_new_overrides to true, and rerun read_input from
|
|
|
|
// the vehicle code however doing so currently breaks the failsafe system on
|
|
|
|
// copter and plane, RC_Channels needs to control failsafes to resolve this
|
2018-04-03 23:16:36 -03:00
|
|
|
}
|
|
|
|
|
2018-04-25 23:06:19 -03:00
|
|
|
void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms)
|
2018-04-03 23:16:36 -03:00
|
|
|
{
|
2018-08-02 08:41:07 -03:00
|
|
|
RC_Channels &_rc = rc();
|
2018-04-03 23:16:36 -03:00
|
|
|
if (chan < NUM_RC_CHANNELS) {
|
2018-08-02 08:41:07 -03:00
|
|
|
_rc.channel(chan)->set_override(value, timestamp_ms);
|
2018-04-03 23:16:36 -03:00
|
|
|
}
|
2018-04-25 23:06:19 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool RC_Channels::has_active_overrides()
|
|
|
|
{
|
2018-08-02 08:41:07 -03:00
|
|
|
RC_Channels &_rc = rc();
|
2018-04-25 23:06:19 -03:00
|
|
|
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
2018-08-02 08:41:07 -03:00
|
|
|
if (_rc.channel(i)->has_override()) {
|
2018-04-25 23:06:19 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-03 23:16:36 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool RC_Channels::receiver_bind(const int dsmMode)
|
|
|
|
{
|
|
|
|
return hal.rcin->rc_bind(dsmMode);
|
|
|
|
}
|
2018-04-13 23:22:14 -03:00
|
|
|
|
|
|
|
|
|
|
|
// support for auxillary switches:
|
|
|
|
// read_aux_switches - checks aux switch positions and invokes configured actions
|
|
|
|
void RC_Channels::read_aux_all()
|
|
|
|
{
|
2018-07-31 21:10:33 -03:00
|
|
|
if (!has_valid_input()) {
|
|
|
|
// exit immediately when no RC input
|
2018-04-13 23:22:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
RC_Channel *c = channel(i);
|
|
|
|
if (c == nullptr) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
c->read_aux();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channels::init_aux_all()
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
RC_Channel *c = channel(i);
|
|
|
|
if (c == nullptr) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
c->init_aux();
|
|
|
|
}
|
|
|
|
reset_mode_switch();
|
|
|
|
}
|
|
|
|
|
|
|
|
//
|
|
|
|
// Support for mode switches
|
|
|
|
//
|
|
|
|
RC_Channel *RC_Channels::flight_mode_channel()
|
|
|
|
{
|
|
|
|
const int8_t num = flight_mode_channel_number();
|
|
|
|
if (num <= 0) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
if (num >= NUM_RC_CHANNELS) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return channel(num-1);
|
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channels::reset_mode_switch()
|
|
|
|
{
|
|
|
|
RC_Channel *c = flight_mode_channel();
|
|
|
|
if (c == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
c->reset_mode_switch();
|
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channels::read_mode_switch()
|
|
|
|
{
|
2018-07-31 21:10:33 -03:00
|
|
|
if (!has_valid_input()) {
|
|
|
|
// exit immediately when no RC input
|
2018-04-13 23:22:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
RC_Channel *c = flight_mode_channel();
|
|
|
|
if (c == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
c->read_mode_switch();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
// singleton instance
|
|
|
|
RC_Channels *RC_Channels::_singleton;
|
|
|
|
|
|
|
|
|
|
|
|
RC_Channels &rc()
|
|
|
|
{
|
|
|
|
return *RC_Channels::get_singleton();
|
|
|
|
}
|