Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/rc_in.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include <AP_RCProtocol/AP_RCProtocol_config.h>1617#ifdef HAL_PERIPH_ENABLE_RCIN1819#ifndef AP_PERIPH_RC1_PORT_DEFAULT20#define AP_PERIPH_RC1_PORT_DEFAULT -121#endif2223#ifndef AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT24#define AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT 025#endif2627#include <AP_RCProtocol/AP_RCProtocol.h>28#include "AP_Periph.h"29#include <dronecan_msgs.h>3031extern const AP_HAL::HAL &hal;3233const AP_Param::GroupInfo Parameters_RCIN::var_info[] {34// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h35// @Param: _PROTOCOLS36// @DisplayName: RC protocols enabled37// @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols.38// @User: Advanced39// @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS40AP_GROUPINFO("_PROTOCOLS", 1, Parameters_RCIN, rcin_protocols, 1),4142// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h43// @Param: _MSGRATE44// @DisplayName: DroneCAN RC Message rate45// @Description: Rate at which RC input is sent via DroneCAN46// @User: Advanced47// @Increment: 148// @Range: 0 25549// @Units: Hz50AP_GROUPINFO("_MSGRATE", 2, Parameters_RCIN, rcin_rate_hz, 50),5152// @Param: 1_PORT53// @DisplayName: RC input port54// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input.55// @Range: 0 1056// @Increment: 157// @User: Advanced58// @RebootRequired: True59AP_GROUPINFO("_PORT", 3, Parameters_RCIN, rcin1_port, AP_PERIPH_RC1_PORT_DEFAULT),6061// @Param: 1_PORT_OPTIONS62// @DisplayName: RC input port serial options63// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.64// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:SwapTXRX, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate65AP_GROUPINFO("1_PORT_OPTIONS", 4, Parameters_RCIN, rcin1_port_options, AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT),66// @RebootRequired: True6768AP_GROUPEND69};7071Parameters_RCIN::Parameters_RCIN(void)72{73AP_Param::setup_object_defaults(this, var_info);74}7576void AP_Periph_FW::rcin_init()77{78if (g_rcin.rcin1_port < 0) {79return;80}8182// init uart for serial RC83auto *uart = hal.serial(g_rcin.rcin1_port);84if (uart == nullptr) {85return;86}8788uart->set_options(g_rcin.rcin1_port_options);8990serial_manager.set_protocol_and_baud(91g_rcin.rcin1_port,92AP_SerialManager::SerialProtocol_RCIN,93115200 // baud doesn't matter; RC Protocol autobauds94);9596auto &rc = AP::RC();97rc.init();98rc.set_rc_protocols(g_rcin.rcin_protocols);99rc.add_uart(uart);100101rcin_initialised = true;102}103104void AP_Periph_FW::rcin_update()105{106if (!rcin_initialised) {107return;108}109110auto &rc = AP::RC();111if (!rc.new_input()) {112return;113}114115// log discovered protocols:116auto new_rc_protocol = rc.protocol_name();117if (new_rc_protocol != rcin_rc_protocol) {118can_printf("Decoding (%s)", new_rc_protocol);119rcin_rc_protocol = new_rc_protocol;120}121122// decimate the input to a parameterized rate123const uint8_t rate_hz = g_rcin.rcin_rate_hz;124if (rate_hz == 0) {125return;126}127128const auto now_ms = AP_HAL::millis();129const auto interval_ms = 1000U / rate_hz;130if (now_ms - rcin_last_sent_RCInput_ms < interval_ms) {131return;132}133rcin_last_sent_RCInput_ms = now_ms;134135// extract data and send CAN packet:136const uint8_t num_channels = rc.num_channels();137uint16_t channels[MAX_RCIN_CHANNELS];138rc.read(channels, num_channels);139const int16_t rssi = rc.get_RSSI();140141can_send_RCInput((uint8_t)rssi, channels, num_channels, rc.failsafe_active(), rssi > 0 && rssi <256);142}143144/*145send an RCInput CAN message146*/147void AP_Periph_FW::can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid)148{149uint16_t status = 0;150if (quality_valid) {151status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_QUALITY_VALID;152}153if (in_failsafe) {154status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_FAILSAFE;155}156157// assemble packet158dronecan_sensors_rc_RCInput pkt {};159pkt.quality = quality;160pkt.status = status;161pkt.rcin.len = nvalues;162for (uint8_t i=0; i<nvalues; i++) {163pkt.rcin.data[i] = values[i];164}165166// encode and send message:167uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE];168169uint16_t total_size = dronecan_sensors_rc_RCInput_encode(&pkt, buffer, !periph.canfdout());170171canard_broadcast(DRONECAN_SENSORS_RC_RCINPUT_SIGNATURE,172DRONECAN_SENSORS_RC_RCINPUT_ID,173CANARD_TRANSFER_PRIORITY_HIGH,174buffer,175total_size);176}177178#endif // HAL_PERIPH_ENABLE_RCIN179180181