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/networking.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_Periph.h"
17
18
#ifdef HAL_PERIPH_ENABLE_NETWORKING
19
20
const AP_Param::GroupInfo Networking_Periph::var_info[] {
21
// @Group:
22
// @Path: ../../libraries/AP_Networking/AP_Networking.cpp
23
AP_SUBGROUPINFO(networking_lib, "", 1, Networking_Periph, AP_Networking),
24
25
/*
26
the NET_Pn_ parameters need to be here as otherwise we
27
are too deep in the parameter tree
28
*/
29
30
#if AP_NETWORKING_NUM_PORTS > 0
31
// @Group: P1_
32
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
33
AP_SUBGROUPINFO(networking_lib.ports[0], "P1_", 2, Networking_Periph, AP_Networking::Port),
34
#endif
35
36
#if AP_NETWORKING_NUM_PORTS > 1
37
// @Group: P2_
38
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
39
AP_SUBGROUPINFO(networking_lib.ports[1], "P2_", 3, Networking_Periph, AP_Networking::Port),
40
#endif
41
42
#if AP_NETWORKING_NUM_PORTS > 2
43
// @Group: P3_
44
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
45
AP_SUBGROUPINFO(networking_lib.ports[2], "P3_", 4, Networking_Periph, AP_Networking::Port),
46
#endif
47
48
#if AP_NETWORKING_NUM_PORTS > 3
49
// @Group: P4_
50
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
51
AP_SUBGROUPINFO(networking_lib.ports[3], "P4_", 5, Networking_Periph, AP_Networking::Port),
52
#endif
53
54
#if AP_NETWORKING_NUM_PORTS > 4
55
// @Group: P5_
56
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
57
AP_SUBGROUPINFO(networking_lib.ports[4], "P5_", 6, Networking_Periph, AP_Networking::Port),
58
#endif
59
60
#if AP_NETWORKING_NUM_PORTS > 5
61
// @Group: P6_
62
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
63
AP_SUBGROUPINFO(networking_lib.ports[5], "P6_", 7, Networking_Periph, AP_Networking::Port),
64
#endif
65
66
#if AP_NETWORKING_NUM_PORTS > 6
67
// @Group: P7_
68
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
69
AP_SUBGROUPINFO(networking_lib.ports[6], "P7_", 8, Networking_Periph, AP_Networking::Port),
70
#endif
71
72
#if AP_NETWORKING_NUM_PORTS > 7
73
// @Group: P8_
74
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
75
AP_SUBGROUPINFO(networking_lib.ports[7], "P8_", 9, Networking_Periph, AP_Networking::Port),
76
#endif
77
78
#if AP_NETWORKING_NUM_PORTS > 8
79
// @Group: P9_
80
// @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp
81
AP_SUBGROUPINFO(networking_lib.ports[8], "P9_", 10, Networking_Periph, AP_Networking::Port),
82
#endif
83
84
85
86
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0
87
// @Group: PASS1_
88
// @Path: networking_passthru.cpp
89
AP_SUBGROUPINFO(passthru[0], "PASS1_", 11, Networking_Periph, Passthru),
90
#endif
91
92
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 1
93
// @Group: PASS2_
94
// @Path: networking_passthru.cpp
95
AP_SUBGROUPINFO(passthru[1], "PASS2_", 12, Networking_Periph, Passthru),
96
#endif
97
98
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 2
99
// @Group: PASS3_
100
// @Path: networking_passthru.cpp
101
AP_SUBGROUPINFO(passthru[2], "PASS3_", 13, Networking_Periph, Passthru),
102
#endif
103
104
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 3
105
// @Group: PASS4_
106
// @Path: networking_passthru.cpp
107
AP_SUBGROUPINFO(passthru[3], "PASS4_", 14, Networking_Periph, Passthru),
108
#endif
109
110
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 4
111
// @Group: PASS5_
112
// @Path: networking_passthru.cpp
113
AP_SUBGROUPINFO(passthru[4], "PASS5_", 15, Networking_Periph, Passthru),
114
#endif
115
116
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 5
117
// @Group: PASS6_
118
// @Path: networking_passthru.cpp
119
AP_SUBGROUPINFO(passthru[5], "PASS6_", 16, Networking_Periph, Passthru),
120
#endif
121
122
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 6
123
// @Group: PASS7_
124
// @Path: networking_passthru.cpp
125
AP_SUBGROUPINFO(passthru[6], "PASS7_", 17, Networking_Periph, Passthru),
126
#endif
127
128
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 7
129
// @Group: PASS8_
130
// @Path: networking_passthru.cpp
131
AP_SUBGROUPINFO(passthru[7], "PASS8_", 18, Networking_Periph, Passthru),
132
#endif
133
134
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 8
135
// @Group: PASS9_
136
// @Path: networking_passthru.cpp
137
AP_SUBGROUPINFO(passthru[8], "PASS9_", 19, Networking_Periph, Passthru),
138
#endif
139
140
#if AP_NETWORKING_BACKEND_PPP
141
// @Param: PPP_PORT
142
// @DisplayName: PPP serial port
143
// @Description: PPP serial port
144
// @Range: -1 10
145
AP_GROUPINFO("PPP_PORT", 20, Networking_Periph, ppp_port, AP_PERIPH_NET_PPP_PORT_DEFAULT),
146
147
// @Param: PPP_BAUD
148
// @DisplayName: PPP serial baudrate
149
// @Description: PPP serial baudrate
150
// @CopyFieldsFrom: SERIAL1_BAUD
151
AP_GROUPINFO("PPP_BAUD", 21, Networking_Periph, ppp_baud, AP_PERIPH_NET_PPP_BAUD_DEFAULT),
152
#endif
153
154
AP_GROUPEND
155
};
156
157
158
void Networking_Periph::init(void)
159
{
160
#if AP_NETWORKING_BACKEND_PPP
161
if (ppp_port >= 0) {
162
AP::serialmanager().set_protocol_and_baud(ppp_port, AP_SerialManager::SerialProtocol_PPP, ppp_baud.get());
163
}
164
#endif
165
166
networking_lib.init();
167
168
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0
169
for (auto &p : passthru) {
170
p.init();
171
}
172
#endif
173
}
174
175
void Networking_Periph::update(void)
176
{
177
networking_lib.update();
178
179
#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0
180
for (auto &p : passthru) {
181
p.update();
182
}
183
#endif
184
185
#if HAL_RAM_RESERVE_START >= 256
186
if (!got_addresses && networking_lib.get_ip_active() != 0) {
187
got_addresses = true;
188
auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
189
if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
190
memset(comms, 0, sizeof(*comms));
191
}
192
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
193
comms->ip = networking_lib.get_ip_active();
194
comms->netmask = networking_lib.get_netmask_active();
195
comms->gateway = networking_lib.get_gateway_active();
196
}
197
#endif // HAL_RAM_RESERVE_START
198
}
199
200
#endif // HAL_PERIPH_ENABLE_NETWORKING
201
202
203