Browse Source

Merge branch 'master' of https://code.google.com/p/ardupilot-mega

mission-4.1.18
Jason Short 14 years ago
parent
commit
9bcbe70e59
  1. 1
      ArduCopter/GCS_Mavlink.pde
  2. 1
      ArduPlane/GCS_Mavlink.pde
  3. 2
      Tools/ArduTracker/APM_Config.h.reference
  4. 13
      libraries/AP_Common/Arduino.mk

1
ArduCopter/GCS_Mavlink.pde

@ -51,6 +51,7 @@ GCS_MAVLINK::update(void) @@ -51,6 +51,7 @@ GCS_MAVLINK::update(void)
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
status.packet_rx_drop_count = 0;
// process received bytes
while(comm_get_available(chan))

1
ArduPlane/GCS_Mavlink.pde

@ -51,6 +51,7 @@ GCS_MAVLINK::update(void) @@ -51,6 +51,7 @@ GCS_MAVLINK::update(void)
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
status.packet_rx_drop_count = 0;
// process received bytes
while(comm_get_available(chan))

2
Tools/ArduTracker/APM_Config.h.reference

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
// Example and reference ArduPilot Mega configuration file
// =======================================================
//
// This file contains documentation and examples for configuration options
// This file contains documentation and examples of configuration options
// supported by the ArduPilot Mega software.
//
// Most of these options are just that - optional. You should create

13
libraries/AP_Common/Arduino.mk

@ -124,7 +124,7 @@ ifeq ($(ARDUINO),) @@ -124,7 +124,7 @@ ifeq ($(ARDUINO),)
#
ifeq ($(SYSTYPE),Darwin)
# use Spotlight to find Arduino.app
ARDUINO_QUERY = 'kMDItemKind == Application && kMDItemDisplayName == Arduino.app'
ARDUINO_QUERY = 'kMDItemKind == Application && kMDItemFSName == Arduino.app'
ARDUINOS := $(addsuffix /Contents/Resources/Java,$(shell mdfind -literal $(ARDUINO_QUERY)))
ifeq ($(ARDUINOS),)
$(error ERROR: Spotlight cannot find Arduino on your system.)
@ -205,10 +205,11 @@ DEPFLAGS = -MD -MT $@ @@ -205,10 +205,11 @@ DEPFLAGS = -MD -MT $@
CXXOPTS = -mcall-prologues -ffunction-sections -fdata-sections -fno-exceptions
COPTS = -mcall-prologues -ffunction-sections -fdata-sections
ASOPTS = -assembler-with-cpp
LISTOPTS = -adhlns=$(@:.o=.lst)
CXXFLAGS = -g -mmcu=$(MCU) $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(CXXOPTS)
CFLAGS = -g -mmcu=$(MCU) $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(COPTS)
ASFLAGS = -g -mmcu=$(MCU) $(DEFINES) $(DEPFLAGS) $(ASOPTS)
CXXFLAGS = -g -mmcu=$(MCU) $(DEFINES) -Wa,$(LISTOPTS) $(OPTFLAGS) $(DEPFLAGS) $(CXXOPTS)
CFLAGS = -g -mmcu=$(MCU) $(DEFINES) -Wa,$(LISTOPTS) $(OPTFLAGS) $(DEPFLAGS) $(COPTS)
ASFLAGS = -g -mmcu=$(MCU) $(DEFINES) $(LISTOPTS) $(DEPFLAGS) $(ASOPTS)
LDFLAGS = -g -mmcu=$(MCU) $(OPTFLAGS) -Wl,--gc-sections -Wl,-Map -Wl,$(SKETCHMAP)
LIBS = -lm
@ -320,7 +321,9 @@ HARDWARE_CORE := $(shell grep $(BOARD).build.core $(BOARDFILE) | cut -d = -f 2) @@ -320,7 +321,9 @@ HARDWARE_CORE := $(shell grep $(BOARD).build.core $(BOARDFILE) | cut -d = -f 2)
UPLOAD_SPEED := $(shell grep $(BOARD).upload.speed $(BOARDFILE) | cut -d = -f 2)
# This simply does not work, so hardcode it to the correct value
#UPLOAD_PROTOCOL := $(shell grep $(BOARD).upload.protocol $(BOARDFILE) | cut -d = -f 2)
UPLOAD_PROTOCOL := arduino
ifeq ($(UPLOAD_PROTOCOL),)
UPLOAD_PROTOCOL := arduino
endif
ifeq ($(MCU),)
$(error ERROR: Could not locate board $(BOARD) in $(BOARDFILE))

Loading…
Cancel
Save