CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/rc_in.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include <AP_RCProtocol/AP_RCProtocol_config.h>
17
18
#ifdef HAL_PERIPH_ENABLE_RCIN
19
20
#ifndef AP_PERIPH_RC1_PORT_DEFAULT
21
#define AP_PERIPH_RC1_PORT_DEFAULT -1
22
#endif
23
24
#ifndef AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT
25
#define AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT 0
26
#endif
27
28
#include <AP_RCProtocol/AP_RCProtocol.h>
29
#include "AP_Periph.h"
30
#include <dronecan_msgs.h>
31
32
extern const AP_HAL::HAL &hal;
33
34
const AP_Param::GroupInfo Parameters_RCIN::var_info[] {
35
// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h
36
// @Param: _PROTOCOLS
37
// @DisplayName: RC protocols enabled
38
// @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.
39
// @User: Advanced
40
// @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:FastSBUS
41
AP_GROUPINFO("_PROTOCOLS", 1, Parameters_RCIN, rcin_protocols, 1),
42
43
// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h
44
// @Param: _MSGRATE
45
// @DisplayName: DroneCAN RC Message rate
46
// @Description: Rate at which RC input is sent via DroneCAN
47
// @User: Advanced
48
// @Increment: 1
49
// @Range: 0 255
50
// @Units: Hz
51
AP_GROUPINFO("_MSGRATE", 2, Parameters_RCIN, rcin_rate_hz, 50),
52
53
// @Param: 1_PORT
54
// @DisplayName: RC input port
55
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input.
56
// @Range: 0 10
57
// @Increment: 1
58
// @User: Advanced
59
// @RebootRequired: True
60
AP_GROUPINFO("_PORT", 3, Parameters_RCIN, rcin1_port, AP_PERIPH_RC1_PORT_DEFAULT),
61
62
// @Param: 1_PORT_OPTIONS
63
// @DisplayName: RC input port serial options
64
// @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.
65
// @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 Streamrate
66
AP_GROUPINFO("1_PORT_OPTIONS", 4, Parameters_RCIN, rcin1_port_options, AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT),
67
// @RebootRequired: True
68
69
AP_GROUPEND
70
};
71
72
Parameters_RCIN::Parameters_RCIN(void)
73
{
74
AP_Param::setup_object_defaults(this, var_info);
75
}
76
77
void AP_Periph_FW::rcin_init()
78
{
79
if (g_rcin.rcin1_port < 0) {
80
return;
81
}
82
83
// init uart for serial RC
84
auto *uart = hal.serial(g_rcin.rcin1_port);
85
if (uart == nullptr) {
86
return;
87
}
88
89
uart->set_options(g_rcin.rcin1_port_options);
90
91
serial_manager.set_protocol_and_baud(
92
g_rcin.rcin1_port,
93
AP_SerialManager::SerialProtocol_RCIN,
94
115200 // baud doesn't matter; RC Protocol autobauds
95
);
96
97
auto &rc = AP::RC();
98
rc.init();
99
rc.set_rc_protocols(g_rcin.rcin_protocols);
100
rc.add_uart(uart);
101
102
rcin_initialised = true;
103
}
104
105
void AP_Periph_FW::rcin_update()
106
{
107
if (!rcin_initialised) {
108
return;
109
}
110
111
auto &rc = AP::RC();
112
if (!rc.new_input()) {
113
return;
114
}
115
116
// log discovered protocols:
117
auto new_rc_protocol = rc.protocol_name();
118
if (new_rc_protocol != rcin_rc_protocol) {
119
can_printf("Decoding (%s)", new_rc_protocol);
120
rcin_rc_protocol = new_rc_protocol;
121
}
122
123
// decimate the input to a parameterized rate
124
const uint8_t rate_hz = g_rcin.rcin_rate_hz;
125
if (rate_hz == 0) {
126
return;
127
}
128
129
const auto now_ms = AP_HAL::millis();
130
const auto interval_ms = 1000U / rate_hz;
131
if (now_ms - rcin_last_sent_RCInput_ms < interval_ms) {
132
return;
133
}
134
rcin_last_sent_RCInput_ms = now_ms;
135
136
// extract data and send CAN packet:
137
const uint8_t num_channels = rc.num_channels();
138
uint16_t channels[MAX_RCIN_CHANNELS];
139
rc.read(channels, num_channels);
140
const int16_t rssi = rc.get_RSSI();
141
142
can_send_RCInput((uint8_t)rssi, channels, num_channels, rc.failsafe_active(), rssi > 0 && rssi <256);
143
}
144
145
/*
146
send an RCInput CAN message
147
*/
148
void AP_Periph_FW::can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid)
149
{
150
uint16_t status = 0;
151
if (quality_valid) {
152
status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_QUALITY_VALID;
153
}
154
if (in_failsafe) {
155
status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_FAILSAFE;
156
}
157
158
// assemble packet
159
dronecan_sensors_rc_RCInput pkt {};
160
pkt.quality = quality;
161
pkt.status = status;
162
pkt.rcin.len = nvalues;
163
for (uint8_t i=0; i<nvalues; i++) {
164
pkt.rcin.data[i] = values[i];
165
}
166
167
// encode and send message:
168
uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE];
169
170
uint16_t total_size = dronecan_sensors_rc_RCInput_encode(&pkt, buffer, !periph.canfdout());
171
172
canard_broadcast(DRONECAN_SENSORS_RC_RCINPUT_SIGNATURE,
173
DRONECAN_SENSORS_RC_RCINPUT_ID,
174
CANARD_TRANSFER_PRIORITY_HIGH,
175
buffer,
176
total_size);
177
}
178
179
#endif // HAL_PERIPH_ENABLE_RCIN
180
181