mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Networking: only enable networking on Linux, ChibiOS and SITL
This commit is contained in:
parent
983a680b2b
commit
702fe9c18d
@ -6,7 +6,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AP_NETWORKING_ENABLED
|
#ifndef AP_NETWORKING_ENABLED
|
||||||
#define AP_NETWORKING_ENABLED ((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL))
|
#define AP_NETWORKING_ENABLED (((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) && !defined(__APPLE__))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED
|
#ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED
|
||||||
|
@ -35,7 +35,7 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32
|
|||||||
uint32_t remaining = len;
|
uint32_t remaining = len;
|
||||||
const uint8_t *ptr = (const uint8_t *)data;
|
const uint8_t *ptr = (const uint8_t *)data;
|
||||||
while (remaining > 0) {
|
while (remaining > 0) {
|
||||||
auto n = driver.uart->write(ptr, remaining);
|
const auto n = driver.uart->write(ptr, remaining);
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
remaining -= n;
|
remaining -= n;
|
||||||
ptr += n;
|
ptr += n;
|
||||||
|
@ -4,6 +4,10 @@ import pathlib
|
|||||||
|
|
||||||
|
|
||||||
def configure(cfg):
|
def configure(cfg):
|
||||||
|
|
||||||
|
if not cfg.env.BOARD_CLASS in ['SITL', 'LINUX', 'ChibiOS']:
|
||||||
|
return
|
||||||
|
|
||||||
extra_src = [
|
extra_src = [
|
||||||
'modules/lwip/src/core/*c',
|
'modules/lwip/src/core/*c',
|
||||||
'modules/lwip/src/core/ipv4/*c',
|
'modules/lwip/src/core/ipv4/*c',
|
||||||
|
Loading…
Reference in New Issue
Block a user