2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file 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 file 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/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
2022-02-20 23:44:56 -04:00
|
|
|
|
|
|
|
#include <hal.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
#include "RCInput.h"
|
|
|
|
#include "hal.h"
|
|
|
|
#include "hwdef/common/ppm.h"
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
2018-01-05 04:55:01 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
#include <AP_IOMCU/AP_IOMCU.h>
|
|
|
|
extern AP_IOMCU iomcu;
|
|
|
|
#endif
|
|
|
|
|
2018-04-26 20:15:19 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2018-11-03 07:00:32 -03:00
|
|
|
|
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
2018-11-02 19:49:41 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2018-11-03 07:00:32 -03:00
|
|
|
#endif
|
2018-04-26 20:15:19 -03:00
|
|
|
|
2018-01-18 15:13:52 -04:00
|
|
|
#define SIG_DETECT_TIMEOUT_US 500000
|
2018-01-05 02:19:51 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCInput::init()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2019-08-27 08:08:25 -03:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2019-08-27 04:43:30 -03:00
|
|
|
AP::RC().init();
|
2019-08-27 08:08:25 -03:00
|
|
|
#endif
|
2019-08-27 04:43:30 -03:00
|
|
|
|
2018-01-17 15:30:21 -04:00
|
|
|
#if HAL_USE_ICU == TRUE
|
|
|
|
//attach timer channel on which the signal will be received
|
|
|
|
sig_reader.attach_capture_timer(&RCIN_ICU_TIMER, RCIN_ICU_CHANNEL, STM32_RCIN_DMA_STREAM, STM32_RCIN_DMA_CHANNEL);
|
2020-01-28 22:23:18 -04:00
|
|
|
pulse_input_enabled = true;
|
2018-01-12 00:43:06 -04:00
|
|
|
#endif
|
2018-04-22 09:43:49 -03:00
|
|
|
|
|
|
|
#if HAL_USE_EICU == TRUE
|
|
|
|
sig_reader.init(&RCININT_EICU_TIMER, RCININT_EICU_CHANNEL);
|
2020-01-28 22:23:18 -04:00
|
|
|
pulse_input_enabled = true;
|
2018-04-22 09:43:49 -03:00
|
|
|
#endif
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
_init = true;
|
|
|
|
}
|
|
|
|
|
2020-01-28 22:23:18 -04:00
|
|
|
/*
|
|
|
|
enable or disable pulse input for RC input. This is used to reduce
|
|
|
|
load when we are decoding R/C via a UART
|
|
|
|
*/
|
|
|
|
void RCInput::pulse_input_enable(bool enable)
|
|
|
|
{
|
|
|
|
pulse_input_enabled = enable;
|
|
|
|
#if HAL_USE_ICU == TRUE || HAL_USE_EICU == TRUE
|
|
|
|
if (!enable) {
|
|
|
|
sig_reader.disable();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
bool RCInput::new_input()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (!_init) {
|
|
|
|
return false;
|
|
|
|
}
|
2020-01-29 17:25:24 -04:00
|
|
|
bool valid;
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
|
|
|
valid = _rcin_timestamp_last_signal != _last_read;
|
|
|
|
_last_read = _rcin_timestamp_last_signal;
|
2018-03-06 18:41:03 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-03-11 11:47:54 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2018-01-05 02:19:51 -04:00
|
|
|
if (!_radio_init) {
|
|
|
|
_radio_init = true;
|
2019-02-10 14:53:21 -04:00
|
|
|
radio = AP_Radio::get_singleton();
|
2018-01-05 02:19:51 -04:00
|
|
|
if (radio) {
|
|
|
|
radio->init();
|
|
|
|
}
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
return valid;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint8_t RCInput::num_channels()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (!_init) {
|
|
|
|
return 0;
|
|
|
|
}
|
2018-03-06 18:41:03 -04:00
|
|
|
return _num_channels;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint16_t RCInput::read(uint8_t channel)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-04-26 20:15:19 -03:00
|
|
|
if (!_init || (channel >= MIN(RC_INPUT_MAX_CHANNELS, _num_channels))) {
|
2018-01-05 02:19:51 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2020-01-28 22:23:18 -04:00
|
|
|
uint16_t v;
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
|
|
|
v = _rc_values[channel];
|
|
|
|
}
|
2018-03-11 11:47:54 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2018-01-05 02:19:51 -04:00
|
|
|
if (radio && channel == 0) {
|
|
|
|
// hook to allow for update of radio on main thread, for mavlink sends
|
|
|
|
radio->update();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
return v;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (!_init) {
|
|
|
|
return false;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
if (len > RC_INPUT_MAX_CHANNELS) {
|
|
|
|
len = RC_INPUT_MAX_CHANNELS;
|
|
|
|
}
|
2020-01-28 22:23:18 -04:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
|
|
|
memcpy(periods, _rc_values, len*sizeof(periods[0]));
|
|
|
|
}
|
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2020-01-29 17:25:24 -04:00
|
|
|
if (radio) {
|
2020-01-28 22:23:18 -04:00
|
|
|
// hook to allow for update of radio on main thread, for mavlink sends
|
|
|
|
radio->update();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2020-01-28 22:23:18 -04:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
return len;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCInput::_timer_tick(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (!_init) {
|
|
|
|
return;
|
|
|
|
}
|
2019-08-27 08:08:25 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
const char *rc_protocol = nullptr;
|
2022-03-27 03:31:20 -03:00
|
|
|
RCSource source = last_source;
|
2019-08-27 08:08:25 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2020-01-29 02:44:53 -04:00
|
|
|
AP_RCProtocol &rcprot = AP::RC();
|
|
|
|
|
2018-11-03 04:10:36 -03:00
|
|
|
#if HAL_USE_ICU == TRUE
|
2020-01-28 22:23:18 -04:00
|
|
|
if (pulse_input_enabled) {
|
|
|
|
const uint32_t *p;
|
|
|
|
uint32_t n;
|
|
|
|
while ((p = (const uint32_t *)sig_reader.sigbuf.readptr(n)) != nullptr) {
|
|
|
|
rcprot.process_pulse_list(p, n*2, sig_reader.need_swap);
|
|
|
|
sig_reader.sigbuf.advance(n);
|
|
|
|
}
|
2018-01-17 15:30:21 -04:00
|
|
|
}
|
2018-11-03 04:10:36 -03:00
|
|
|
#endif
|
2018-01-17 15:30:21 -04:00
|
|
|
|
2018-11-03 04:10:36 -03:00
|
|
|
#if HAL_USE_EICU == TRUE
|
2020-01-28 22:23:18 -04:00
|
|
|
if (pulse_input_enabled) {
|
|
|
|
uint32_t width_s0, width_s1;
|
|
|
|
while(sig_reader.read(width_s0, width_s1)) {
|
|
|
|
rcprot.process_pulse(width_s0, width_s1);
|
|
|
|
}
|
2018-11-03 04:10:36 -03:00
|
|
|
}
|
|
|
|
#endif
|
2018-11-05 01:44:34 -04:00
|
|
|
|
2023-02-07 21:54:58 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
2022-03-17 04:01:03 -03:00
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
const bool have_iocmu_rc = (_rcin_last_iomcu_ms != 0 && now - _rcin_last_iomcu_ms < 400);
|
|
|
|
if (!have_iocmu_rc) {
|
|
|
|
_rcin_last_iomcu_ms = 0;
|
|
|
|
}
|
2023-02-07 21:54:58 -04:00
|
|
|
#else
|
|
|
|
const bool have_iocmu_rc = false;
|
|
|
|
#endif
|
2022-03-17 04:01:03 -03:00
|
|
|
|
2022-03-27 03:30:19 -03:00
|
|
|
if (rcprot.new_input() && !have_iocmu_rc) {
|
2020-01-28 22:23:18 -04:00
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
2018-01-05 02:19:51 -04:00
|
|
|
_rcin_timestamp_last_signal = AP_HAL::micros();
|
2020-01-28 22:23:18 -04:00
|
|
|
_num_channels = rcprot.num_channels();
|
2018-11-02 08:23:53 -03:00
|
|
|
_num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS);
|
2020-01-28 22:23:18 -04:00
|
|
|
rcprot.read(_rc_values, _num_channels);
|
|
|
|
_rssi = rcprot.get_RSSI();
|
2021-07-12 16:03:44 -03:00
|
|
|
_rx_link_quality = rcprot.get_rx_link_quality();
|
2018-11-03 02:46:02 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
2020-01-28 22:23:18 -04:00
|
|
|
rc_protocol = rcprot.protocol_name();
|
2022-03-27 03:31:20 -03:00
|
|
|
source = rcprot.using_uart() ? RCSource::RCPROT_BYTES : RCSource::RCPROT_PULSES;
|
2018-11-03 02:46:02 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2019-08-27 08:08:25 -03:00
|
|
|
#endif // HAL_BUILD_AP_PERIPH
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-03-11 11:47:54 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2022-03-27 03:31:20 -03:00
|
|
|
if (radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc) {
|
2018-01-05 02:19:51 -04:00
|
|
|
last_radio_us = radio->last_recv_us();
|
2020-01-28 22:23:18 -04:00
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
2018-01-05 02:19:51 -04:00
|
|
|
_rcin_timestamp_last_signal = last_radio_us;
|
|
|
|
_num_channels = radio->num_channels();
|
2018-11-02 08:23:53 -03:00
|
|
|
_num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS);
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i=0; i<_num_channels; i++) {
|
|
|
|
_rc_values[i] = radio->read(i);
|
|
|
|
}
|
2022-03-27 03:31:20 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
source = RCSource::APRADIO;
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
2020-01-28 22:23:18 -04:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
|
|
|
if (AP_BoardConfig::io_enabled() &&
|
|
|
|
iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS)) {
|
|
|
|
_rcin_timestamp_last_signal = last_iomcu_us;
|
2022-03-17 04:01:03 -03:00
|
|
|
_rcin_last_iomcu_ms = now;
|
2018-11-05 01:44:34 -04:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
2020-01-28 22:23:18 -04:00
|
|
|
rc_protocol = iomcu.get_rc_protocol();
|
|
|
|
_rssi = iomcu.get_RSSI();
|
2022-03-27 03:31:20 -03:00
|
|
|
source = RCSource::IOMCU;
|
2018-11-05 01:44:34 -04:00
|
|
|
#endif
|
2020-01-28 22:23:18 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
#endif
|
2018-11-05 01:44:34 -04:00
|
|
|
|
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
2022-03-27 03:31:20 -03:00
|
|
|
if (rc_protocol && (rc_protocol != last_protocol || source != last_source)) {
|
2018-11-05 01:44:34 -04:00
|
|
|
last_protocol = rc_protocol;
|
2022-03-27 03:31:20 -03:00
|
|
|
last_source = source;
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s(%u)", last_protocol, unsigned(source));
|
2018-11-05 01:44:34 -04:00
|
|
|
}
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
// note, we rely on the vehicle code checking new_input()
|
|
|
|
// and a timeout for the last valid input to handle failsafe
|
|
|
|
}
|
|
|
|
|
2018-04-10 03:15:23 -03:00
|
|
|
/*
|
|
|
|
start a bind operation, if supported
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
bool RCInput::rc_bind(int dsmMode)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-08-26 12:05:17 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2020-01-28 22:23:18 -04:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(rcin_mutex);
|
|
|
|
if (AP_BoardConfig::io_enabled()) {
|
|
|
|
iomcu.bind_dsm(dsmMode);
|
|
|
|
}
|
2018-08-26 12:05:17 -03:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-08-27 08:08:25 -03:00
|
|
|
#ifndef HAL_BUILD_AP_PERIPH
|
2018-04-10 03:15:23 -03:00
|
|
|
// ask AP_RCProtocol to start a bind
|
2019-08-27 04:43:30 -03:00
|
|
|
AP::RC().start_bind();
|
2019-08-27 08:08:25 -03:00
|
|
|
#endif
|
2019-08-27 04:43:30 -03:00
|
|
|
|
2018-03-11 11:47:54 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2018-01-05 02:19:51 -04:00
|
|
|
if (radio) {
|
|
|
|
radio->start_recv_bind();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|