SITL: Added comment to clarify IMU acceleration value
[ardupilot.git] / libraries / AP_Networking / AP_Networking.cpp
blobc5a8cb974f1cdf866a67f3ab183c06320cd4d0f5
2 #include "AP_Networking_Config.h"
4 #if AP_NETWORKING_ENABLED
6 #include "AP_Networking.h"
7 #include "AP_Networking_Backend.h"
8 #include <GCS_MAVLink/GCS.h>
9 #include <AP_Math/crc.h>
10 #include <AP_InternalError/AP_InternalError.h>
11 #include <AP_Filesystem/AP_Filesystem.h>
12 #include <AP_HAL/CANIface.h>
14 extern const AP_HAL::HAL& hal;
16 #if AP_NETWORKING_BACKEND_CHIBIOS
17 #include "AP_Networking_ChibiOS.h"
18 #include <hal_mii.h>
19 #endif
21 #include <lwipopts.h>
22 #include <errno.h>
25 #include <AP_HAL/utility/Socket.h>
27 #if AP_NETWORKING_BACKEND_PPP
28 #include "AP_Networking_PPP.h"
29 #endif
31 #if AP_NETWORKING_BACKEND_SITL
32 #include "AP_Networking_SITL.h"
33 #endif
35 const AP_Param::GroupInfo AP_Networking::var_info[] = {
36 // @Param: ENABLE
37 // @DisplayName: Networking Enable
38 // @Description: Networking Enable
39 // @Values: 0:Disable,1:Enable
40 // @RebootRequired: True
41 // @User: Advanced
42 AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE),
44 #if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
45 // @Group: IPADDR
46 // @Path: AP_Networking_address.cpp
47 AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4),
49 // @Param: NETMASK
50 // @DisplayName: IP Subnet mask
51 // @Description: Allows setting static subnet mask. The value is a count of consecutive bits. Examples: 24 = 255.255.255.0, 16 = 255.255.0.0
52 // @Range: 0 32
53 // @RebootRequired: True
54 // @User: Advanced
55 AP_GROUPINFO("NETMASK", 3, AP_Networking, param.netmask, AP_NETWORKING_DEFAULT_NETMASK),
57 #if AP_NETWORKING_DHCP_AVAILABLE
58 // @Param: DHCP
59 // @DisplayName: DHCP client
60 // @Description: Enable/Disable DHCP client
61 // @Values: 0:Disable, 1:Enable
62 // @RebootRequired: True
63 // @User: Advanced
64 AP_GROUPINFO("DHCP", 4, AP_Networking, param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE),
65 #endif
67 // @Group: GWADDR
68 // @Path: AP_Networking_address.cpp
69 AP_SUBGROUPINFO(param.gwaddr, "GWADDR", 5, AP_Networking, AP_Networking_IPV4),
71 // @Group: MACADDR
72 // @Path: AP_Networking_macaddr.cpp
73 AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC),
74 #endif // AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
76 #if AP_NETWORKING_TESTS_ENABLED
77 // @Param: TESTS
78 // @DisplayName: Test enable flags
79 // @Description: Enable/Disable networking tests
80 // @Bitmask: 0:UDP echo test,1:TCP echo test, 2:TCP discard test, 3:TCP reflect test
81 // @RebootRequired: True
82 // @User: Advanced
83 AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0),
85 // @Group: TEST_IP
86 // @Path: AP_Networking_address.cpp
87 AP_SUBGROUPINFO(param.test_ipaddr, "TEST_IP", 8, AP_Networking, AP_Networking_IPV4),
88 #endif
90 // @Param: OPTIONS
91 // @DisplayName: Networking options
92 // @Description: Networking options
93 // @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast endpoint, 2:Enable CAN2 multicast endpoint, 3:Enable CAN1 multicast bridged, 4:Enable CAN2 multicast bridged
94 // @RebootRequired: True
95 // @User: Advanced
96 AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0),
98 #if AP_NETWORKING_PPP_GATEWAY_ENABLED
99 // @Group: REMPPP_IP
100 // @Path: AP_Networking_address.cpp
101 AP_SUBGROUPINFO(param.remote_ppp_ip, "REMPPP_IP", 10, AP_Networking, AP_Networking_IPV4),
102 #endif
104 AP_GROUPEND
108 constructor
110 AP_Networking::AP_Networking(void)
112 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
113 if (singleton != nullptr) {
114 AP_HAL::panic("AP_Networking must be singleton");
116 #endif
117 singleton = this;
118 AP_Param::setup_object_defaults(this, var_info);
122 initialise networking subsystem
124 void AP_Networking::init()
126 if (!param.enabled || backend != nullptr) {
127 return;
130 #if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
131 // set default MAC Address as lower 3 bytes of the CRC of the UID
132 uint8_t uid[50];
133 uint8_t uid_len = sizeof(uid);
134 if (hal.util->get_system_id_unformatted(uid, uid_len)) {
135 union {
136 uint8_t bytes[4];
137 uint32_t value32;
138 } crc;
139 crc.value32 = crc_crc32(0, uid, uid_len);
141 param.macaddr.set_default_address_byte(3, crc.bytes[0]);
142 param.macaddr.set_default_address_byte(4, crc.bytes[1]);
143 param.macaddr.set_default_address_byte(5, crc.bytes[2]);
145 #endif
147 #if AP_NETWORKING_PPP_GATEWAY_ENABLED
148 if (option_is_set(OPTION::PPP_ETHERNET_GATEWAY)) {
150 when we are a PPP/Ethernet gateway we bring up the ethernet first
152 backend = NEW_NOTHROW AP_Networking_ChibiOS(*this);
153 backend_PPP = NEW_NOTHROW AP_Networking_PPP(*this);
155 #endif
158 #if AP_NETWORKING_BACKEND_PPP
159 if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) {
160 backend = NEW_NOTHROW AP_Networking_PPP(*this);
162 #endif
164 #if AP_NETWORKING_BACKEND_CHIBIOS
165 if (backend == nullptr) {
166 backend = NEW_NOTHROW AP_Networking_ChibiOS(*this);
168 #endif
169 #if AP_NETWORKING_BACKEND_SITL
170 if (backend == nullptr) {
171 backend = NEW_NOTHROW AP_Networking_SITL(*this);
173 #endif
175 if (backend == nullptr) {
176 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend failed");
177 return;
180 if (!backend->init()) {
181 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend init failed");
182 // the backend init function creates a thread which references the backend pointer; that thread may be running so don't remove the backend allocation.
183 backend = nullptr;
184 return;
187 #if AP_NETWORKING_PPP_GATEWAY_ENABLED
188 if (backend_PPP != nullptr && !backend_PPP->init()) {
189 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend_PPP init failed");
190 backend_PPP = nullptr;
192 #endif
194 announce_address_changes();
196 GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized");
198 #if AP_NETWORKING_TESTS_ENABLED
199 start_tests();
200 #endif
202 #if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
203 if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT) || option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
204 // get mask of enabled buses
205 uint8_t bus_mask = 0;
206 if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
207 bus_mask |= (1U<<0);
209 if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
210 bus_mask |= (1U<<1);
212 mcast_server.start(bus_mask);
214 #endif
216 #if AP_NETWORKING_REGISTER_PORT_ENABLED
217 // init network mapped serialmanager ports
218 ports_init();
219 #endif
223 check if we should announce changes to IP addresses
225 void AP_Networking::announce_address_changes()
227 const auto &as = backend->activeSettings;
229 if (as.last_change_ms == 0 || as.last_change_ms == announce_ms) {
230 // nothing changed and we've already printed it at least once. Nothing to do.
231 return;
234 #if AP_HAVE_GCS_SEND_TEXT
235 char ipstr[16];
236 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr)));
237 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", SocketAPM::inet_addr_to_str(get_netmask_active(), ipstr, sizeof(ipstr)));
238 GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", SocketAPM::inet_addr_to_str(get_gateway_active(), ipstr, sizeof(ipstr)));
239 #endif
241 announce_ms = as.last_change_ms;
245 update called at 10Hz
247 void AP_Networking::update()
249 if (!is_healthy()) {
250 return;
252 backend->update();
253 announce_address_changes();
256 uint32_t AP_Networking::convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount)
258 if (netmask_bitcount >= 32) {
259 return 0xFFFFFFFFU;
261 return ~((1U<<(32U-netmask_bitcount))-1U);
264 uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip)
266 uint32_t netmask_bitcount = 0;
267 for (uint32_t i=0; i<32; i++) {
268 // note, netmask LSB is IP MSB
269 if ((netmask_ip & (1UL<<i)) == 0) {
270 break;
272 netmask_bitcount++;
274 return netmask_bitcount;
278 convert a string to an ethernet MAC address
280 bool AP_Networking::convert_str_to_macaddr(const char *mac_str, uint8_t addr[6])
282 if (strlen(mac_str) != 17) {
283 return false;
285 char s2[18];
286 strncpy(s2, mac_str, sizeof(s2)-1);
287 s2[17] = 0;
288 char *ptr = nullptr;
289 const char *s = strtok_r(s2, ":", &ptr);
290 for (uint8_t i=0; i<6; i++) {
291 if (s == nullptr) {
292 return false;
294 auto v = strtoul(s, nullptr, 16);
295 if (v > 255) {
296 return false;
298 addr[i] = v;
299 s = strtok_r(nullptr, ":", &ptr);
301 return true;
304 // returns the 32bit value of the active IP address that is currently in use
305 uint32_t AP_Networking::get_ip_active() const
307 return backend?backend->activeSettings.ip:0;
310 // returns the 32bit value of the active Netmask that is currently in use
311 uint32_t AP_Networking::get_netmask_active() const
313 return backend?backend->activeSettings.nm:0;
316 uint32_t AP_Networking::get_gateway_active() const
318 return backend?backend->activeSettings.gw:0;
322 wait for networking to be active
324 void AP_Networking::startup_wait(void) const
326 if (hal.scheduler->in_main_thread()) {
327 INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
328 return;
330 while (!hal.scheduler->is_system_initialized()) {
331 hal.scheduler->delay(100);
333 #if AP_NETWORKING_BACKEND_CHIBIOS
334 do {
335 hal.scheduler->delay(250);
336 } while (get_ip_active() == 0);
337 #endif
341 send the rest of a file to a socket
343 bool AP_Networking::sendfile(SocketAPM *sock, int fd)
345 WITH_SEMAPHORE(sem);
346 if (sendfile_buf == nullptr) {
347 uint32_t bufsize = AP_NETWORKING_SENDFILE_BUFSIZE;
348 do {
349 sendfile_buf = (uint8_t *)hal.util->malloc_type(bufsize, AP_HAL::Util::MEM_FILESYSTEM);
350 if (sendfile_buf != nullptr) {
351 sendfile_bufsize = bufsize;
352 break;
354 bufsize /= 2;
355 } while (bufsize >= 4096);
356 if (sendfile_buf == nullptr) {
357 return false;
360 if (!sendfile_thread_started) {
361 if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::sendfile_check, void),
362 "sendfile",
363 2048, AP_HAL::Scheduler::PRIORITY_UART, 0)) {
364 return false;
366 sendfile_thread_started = true;
368 for (auto &s : sendfiles) {
369 if (s.sock == nullptr) {
370 s.sock = sock->duplicate();
371 if (s.sock == nullptr) {
372 return false;
374 s.fd = fd;
375 return true;
378 return false;
381 void AP_Networking::SendFile::close(void)
383 AP::FS().close(fd);
384 delete sock;
385 sock = nullptr;
388 #include <stdio.h>
390 check for sendfile updates
392 void AP_Networking::sendfile_check(void)
394 while (true) {
395 hal.scheduler->delay(1);
396 WITH_SEMAPHORE(sem);
397 bool none_active = true;
398 for (auto &s : sendfiles) {
399 if (s.sock == nullptr) {
400 continue;
402 none_active = false;
403 if (!s.sock->pollout(0)) {
404 continue;
406 const auto nread = AP::FS().read(s.fd, sendfile_buf, sendfile_bufsize);
407 if (nread <= 0) {
408 s.close();
409 continue;
411 const auto nsent = s.sock->send(sendfile_buf, nread);
412 if (nsent <= 0) {
413 s.close();
414 continue;
416 if (nsent < nread) {
417 AP::FS().lseek(s.fd, nsent - nread, SEEK_CUR);
420 if (none_active) {
421 free(sendfile_buf);
422 sendfile_buf = nullptr;
427 AP_Networking *AP_Networking::singleton;
429 namespace AP
431 AP_Networking &network()
433 return *AP_Networking::get_singleton();
438 debug printfs from LWIP
440 int ap_networking_printf(const char *fmt, ...)
442 WITH_SEMAPHORE(AP::network().get_semaphore());
443 #ifdef AP_NETWORKING_LWIP_DEBUG_FILE
444 static int fd = -1;
445 if (fd == -1) {
446 fd = AP::FS().open(AP_NETWORKING_LWIP_DEBUG_FILE, O_WRONLY|O_CREAT|O_TRUNC, 0644);
447 if (fd == -1) {
448 return -1;
451 va_list ap;
452 va_start(ap, fmt);
453 vdprintf(fd, fmt, ap);
454 va_end(ap);
455 #else
456 va_list ap;
457 va_start(ap, fmt);
458 hal.console->vprintf(fmt, ap);
459 va_end(ap);
460 #endif
461 return 0;
464 // address to string using a static return buffer
465 const char *AP_Networking::address_to_str(uint32_t addr)
467 static char buf[16]; // 16 for aaa.bbb.ccc.ddd
468 return SocketAPM::inet_addr_to_str(addr, buf, sizeof(buf));
471 #ifdef LWIP_PLATFORM_ASSERT
472 void ap_networking_platform_assert(const char *msg, int line, const char *file)
474 AP_HAL::panic("LWIP: %s: %s:%u", msg, file, line);
476 #endif
478 #endif // AP_NETWORKING_ENABLED