mirror of https://github.com/ArduPilot/ardupilot
desktop: make desktop build more portable
this should help on MacOS thanks to MikeS for his assistance
This commit is contained in:
parent
0e447b12a2
commit
5194fe489d
|
@ -24,6 +24,14 @@
|
|||
# SUCH DAMAGE.
|
||||
#
|
||||
|
||||
#
|
||||
# Save the system type for later use.
|
||||
#
|
||||
SYSTYPE := $(shell uname)
|
||||
|
||||
# force LANG to C so awk works sanely on MacOS
|
||||
export LANG=C
|
||||
|
||||
#
|
||||
# Locate the sketch sources based on the initial Makefile's path
|
||||
#
|
||||
|
@ -85,13 +93,18 @@ ifneq ($(MAKECMDGOALS),configure)
|
|||
HARDWARE=desktop
|
||||
BOARD=desktop
|
||||
|
||||
CXX := g++
|
||||
CC := gcc
|
||||
AS := gcc
|
||||
AR := ar
|
||||
LD := g++
|
||||
GDB := gdb
|
||||
OBJCOPY := objcopy
|
||||
ifeq ($(SYSTYPE),Darwin)
|
||||
CXX := c++
|
||||
CC := cc
|
||||
AS := cc
|
||||
AR := ar
|
||||
endif
|
||||
|
||||
CXX ?= g++
|
||||
CC ?= gcc
|
||||
AS ?= gcc
|
||||
AR ?= ar
|
||||
LD := $(CXX)
|
||||
|
||||
# Find awk
|
||||
AWK ?= gawk
|
||||
|
@ -114,7 +127,7 @@ ASOPTS = -assembler-with-cpp
|
|||
CXXFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(CXXOPTS)
|
||||
CFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(COPTS)
|
||||
ASFLAGS = -g $(DEFINES) $(DEPFLAGS) $(ASOPTS)
|
||||
LDFLAGS = -g $(OPTFLAGS) -Wl,--gc-sections -Wl,-Map -Wl,$(SKETCHMAP)
|
||||
LDFLAGS = -g $(OPTFLAGS)
|
||||
|
||||
LIBS = -lm
|
||||
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
#include "FastSerial.h"
|
||||
#include "WProgram.h"
|
||||
#include <unistd.h>
|
||||
#include <pty.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <stdio.h>
|
||||
|
@ -62,6 +61,10 @@
|
|||
# define FS_MAX_PORTS 1
|
||||
#endif
|
||||
|
||||
#ifndef MSG_NOSIGNAL
|
||||
# define MSG_NOSIGNAL 0
|
||||
#endif
|
||||
|
||||
static struct tcp_state {
|
||||
bool connected; // true if a client has connected
|
||||
int listen_fd; // socket we are listening on
|
||||
|
@ -132,7 +135,7 @@ static void tcp_start_connection(unsigned int serial_port, bool wait_for_connect
|
|||
fprintf(stderr, "accept() error - %s", strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
setsockopt(s->fd, SOL_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
setsockopt(s->fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
s->connected = true;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue