├── .editorconfig
├── .gitattributes
├── .github
├── CONTRIBUTING.md
└── ISSUE_TEMPLATE.md
├── .gitignore
├── .gitmodules
├── .pydevproject
├── .travis.yml
├── APMrover2
├── APM_Config.h
├── APMrover2.cpp
├── GCS_Mavlink.cpp
├── GCS_Mavlink.h
├── Log.cpp
├── Makefile
├── Makefile.waf
├── Parameters.cpp
├── Parameters.h
├── Parameters.pde
├── Rover.cpp
├── Rover.h
├── Steering.cpp
├── capabilities.cpp
├── commands.cpp
├── commands_logic.cpp
├── commands_process.cpp
├── compat.cpp
├── compat.h
├── config.h
├── control_modes.cpp
├── createTags
├── defines.h
├── events.cpp
├── failsafe.cpp
├── make.inc
├── navigation.cpp
├── radio.cpp
├── release-notes.txt
├── sensors.cpp
├── setup.cpp
├── system.cpp
├── test.cpp
├── version.h
└── wscript
├── AntennaTracker
├── APM_Config.h
├── AntennaTracker.cpp
├── AntennaTracker.txt
├── GCS_Mavlink.cpp
├── GCS_Mavlink.h
├── Log.cpp
├── Makefile
├── Parameters.cpp
├── Parameters.h
├── Parameters.pde
├── ReleaseNotes.txt
├── Tracker.h
├── capabilities.cpp
├── config.h
├── control_auto.cpp
├── control_manual.cpp
├── control_scan.cpp
├── control_servo_test.cpp
├── defines.h
├── make.inc
├── radio.cpp
├── sensors.cpp
├── servos.cpp
├── system.cpp
├── tracking.cpp
├── version.h
└── wscript
├── ArduCopter
├── .gitignore
├── APM_Config.h
├── APM_Config_mavlink_hil.h
├── AP_State.cpp
├── ArduCopter.cpp
├── Attitude.cpp
├── Copter.cpp
├── Copter.h
├── GCS_Mavlink.cpp
├── GCS_Mavlink.h
├── Log.cpp
├── Makefile
├── Makefile.waf
├── Parameters.cpp
├── Parameters.h
├── Parameters.pde
├── ReleaseNotes.txt
├── UserCode.cpp
├── UserVariables.h
├── adsb.cpp
├── arming_checks.cpp
├── baro_ground_effect.cpp
├── capabilities.cpp
├── commands.cpp
├── commands_logic.cpp
├── compassmot.cpp
├── compat.cpp
├── config.h
├── control_acro.cpp
├── control_althold.cpp
├── control_auto.cpp
├── control_autotune.cpp
├── control_brake.cpp
├── control_circle.cpp
├── control_drift.cpp
├── control_flip.cpp
├── control_guided.cpp
├── control_land.cpp
├── control_loiter.cpp
├── control_poshold.cpp
├── control_rtl.cpp
├── control_sport.cpp
├── control_stabilize.cpp
├── control_throw.cpp
├── crash_check.cpp
├── defines.h
├── ekf_check.cpp
├── esc_calibration.cpp
├── events.cpp
├── failsafe.cpp
├── fence.cpp
├── flight_mode.cpp
├── heli.cpp
├── heli_control_acro.cpp
├── heli_control_stabilize.cpp
├── inertia.cpp
├── land_detector.cpp
├── landing_gear.cpp
├── leds.cpp
├── make.inc
├── motor_test.cpp
├── motors.cpp
├── navigation.cpp
├── perf_info.cpp
├── position_vector.cpp
├── precision_landing.cpp
├── radio.cpp
├── recovery.cpp
├── sensors.cpp
├── setup.cpp
├── switches.cpp
├── system.cpp
├── takeoff.cpp
├── terrain.cpp
├── test.cpp
├── tuning.cpp
├── version.h
└── wscript
├── ArduPlane
├── APM_Config.h
├── APM_Config.h.reference
├── ArduPlane.cpp
├── Attitude.cpp
├── GCS_Mavlink.cpp
├── GCS_Mavlink.h
├── Log.cpp
├── Makefile
├── Makefile.waf
├── Parameters.cpp
├── Parameters.h
├── Parameters.pde
├── Plane.cpp
├── Plane.h
├── adsb.cpp
├── altitude.cpp
├── arming_checks.cpp
├── capabilities.cpp
├── commands.cpp
├── commands_logic.cpp
├── config.h
├── control_modes.cpp
├── createTags
├── defines.h
├── events.cpp
├── failsafe.cpp
├── geofence.cpp
├── is_flying.cpp
├── landing.cpp
├── make.inc
├── motor_test.cpp
├── navigation.cpp
├── parachute.cpp
├── px4_mixer.cpp
├── quadplane.cpp
├── quadplane.h
├── radio.cpp
├── release-notes.txt
├── sensors.cpp
├── setup.cpp
├── system.cpp
├── takeoff.cpp
├── test.cpp
├── tiltrotor.cpp
├── tuning.cpp
├── tuning.h
├── version.h
└── wscript
├── BUILD.md
├── COPYING.txt
├── Doxyfile.in
├── Makefile
├── Makefile.waf
├── README.md
├── Tools
├── APM2_2560_bootloader
│ ├── FLASH.txt
│ ├── License.txt
│ ├── Makefile
│ ├── README.txt
│ ├── avrinterruptnames.h
│ ├── command.h
│ └── stk500boot.c
├── APM_radio_test
│ ├── APM_radio_test.pde
│ └── Makefile
├── ArduPPM
│ ├── ATMega328p
│ │ ├── Encoder-PPM-v3.c
│ │ ├── Encoder-PPM.c
│ │ ├── Makefile
│ │ ├── manual.txt
│ │ └── readme.txt
│ ├── ATMega32U2
│ │ ├── Bootloaders
│ │ │ └── arduino-usbdfu
│ │ │ │ ├── Arduino-usbdfu.c
│ │ │ │ ├── Arduino-usbdfu.h
│ │ │ │ ├── Board
│ │ │ │ └── LEDs.h
│ │ │ │ ├── Descriptors.c
│ │ │ │ ├── Descriptors.h
│ │ │ │ ├── makefile
│ │ │ │ └── readme.txt
│ │ ├── Drivers
│ │ │ ├── Arduino_MEGA_2560.inf
│ │ │ ├── amd64
│ │ │ │ └── libusb0.sys
│ │ │ ├── atmel_usb_dfu.inf
│ │ │ ├── ia64
│ │ │ │ └── libusb0.sys
│ │ │ └── x86
│ │ │ │ └── libusb0.sys
│ │ ├── LUFA.pnproj
│ │ ├── LUFA
│ │ │ ├── Common
│ │ │ │ ├── Attributes.h
│ │ │ │ ├── BoardTypes.h
│ │ │ │ └── Common.h
│ │ │ ├── Doxygen.conf
│ │ │ ├── DriverStubs
│ │ │ │ ├── Buttons.h
│ │ │ │ ├── Dataflash.h
│ │ │ │ ├── Joystick.h
│ │ │ │ └── LEDs.h
│ │ │ ├── Drivers
│ │ │ │ ├── Board
│ │ │ │ │ ├── ATAVRUSBRF01
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── BENITO
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── BUMBLEB
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ ├── Joystick.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── Buttons.h
│ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ ├── EVK527
│ │ │ │ │ │ ├── AT45DB321C.h
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ │ ├── Joystick.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── JMDBU2
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── Joystick.h
│ │ │ │ │ ├── LEDs.h
│ │ │ │ │ ├── RZUSBSTICK
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── STK525
│ │ │ │ │ │ ├── AT45DB321C.h
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ │ ├── Joystick.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── STK526
│ │ │ │ │ │ ├── AT45DB642D.h
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ │ ├── Joystick.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── TEENSY
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── Temperature.c
│ │ │ │ │ ├── Temperature.h
│ │ │ │ │ ├── USBKEY
│ │ │ │ │ │ ├── AT45DB642D.h
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ │ ├── Joystick.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ ├── USBTINYMKII
│ │ │ │ │ │ ├── Buttons.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ │ └── XPLAIN
│ │ │ │ │ │ ├── AT45DB642D.h
│ │ │ │ │ │ ├── Dataflash.h
│ │ │ │ │ │ └── LEDs.h
│ │ │ │ ├── Misc
│ │ │ │ │ └── TerminalCodes.h
│ │ │ │ ├── Peripheral
│ │ │ │ │ ├── ADC.h
│ │ │ │ │ ├── AVRU4U6U7
│ │ │ │ │ │ ├── ADC.h
│ │ │ │ │ │ └── TWI.h
│ │ │ │ │ ├── SPI.h
│ │ │ │ │ ├── Serial.c
│ │ │ │ │ ├── Serial.h
│ │ │ │ │ ├── SerialStream.c
│ │ │ │ │ ├── SerialStream.h
│ │ │ │ │ ├── TWI.c
│ │ │ │ │ └── TWI.h
│ │ │ │ └── USB
│ │ │ │ │ ├── Class
│ │ │ │ │ ├── Audio.h
│ │ │ │ │ ├── CDC.h
│ │ │ │ │ ├── Common
│ │ │ │ │ │ ├── Audio.h
│ │ │ │ │ │ ├── CDC.h
│ │ │ │ │ │ ├── HID.h
│ │ │ │ │ │ ├── MIDI.h
│ │ │ │ │ │ ├── MassStorage.h
│ │ │ │ │ │ ├── Printer.h
│ │ │ │ │ │ ├── RNDIS.h
│ │ │ │ │ │ ├── RNDISConstants.h
│ │ │ │ │ │ └── StillImage.h
│ │ │ │ │ ├── Device
│ │ │ │ │ │ ├── Audio.c
│ │ │ │ │ │ ├── Audio.h
│ │ │ │ │ │ ├── CDC.c
│ │ │ │ │ │ ├── CDC.h
│ │ │ │ │ │ ├── HID.c
│ │ │ │ │ │ ├── HID.h
│ │ │ │ │ │ ├── MIDI.c
│ │ │ │ │ │ ├── MIDI.h
│ │ │ │ │ │ ├── MassStorage.c
│ │ │ │ │ │ ├── MassStorage.h
│ │ │ │ │ │ ├── RNDIS.c
│ │ │ │ │ │ └── RNDIS.h
│ │ │ │ │ ├── HID.h
│ │ │ │ │ ├── Host
│ │ │ │ │ │ ├── CDC.c
│ │ │ │ │ │ ├── CDC.h
│ │ │ │ │ │ ├── HID.c
│ │ │ │ │ │ ├── HID.h
│ │ │ │ │ │ ├── HIDParser.c
│ │ │ │ │ │ ├── HIDParser.h
│ │ │ │ │ │ ├── HIDReportData.h
│ │ │ │ │ │ ├── MIDI.c
│ │ │ │ │ │ ├── MIDI.h
│ │ │ │ │ │ ├── MassStorage.c
│ │ │ │ │ │ ├── MassStorage.h
│ │ │ │ │ │ ├── Printer.c
│ │ │ │ │ │ ├── Printer.h
│ │ │ │ │ │ ├── RNDIS.c
│ │ │ │ │ │ ├── RNDIS.h
│ │ │ │ │ │ ├── StillImage.c
│ │ │ │ │ │ └── StillImage.h
│ │ │ │ │ ├── MIDI.h
│ │ │ │ │ ├── MassStorage.h
│ │ │ │ │ ├── Printer.h
│ │ │ │ │ ├── RNDIS.h
│ │ │ │ │ └── StillImage.h
│ │ │ │ │ ├── HighLevel
│ │ │ │ │ ├── ConfigDescriptor.c
│ │ │ │ │ ├── ConfigDescriptor.h
│ │ │ │ │ ├── DeviceStandardReq.c
│ │ │ │ │ ├── DeviceStandardReq.h
│ │ │ │ │ ├── Events.c
│ │ │ │ │ ├── Events.h
│ │ │ │ │ ├── HostStandardReq.c
│ │ │ │ │ ├── HostStandardReq.h
│ │ │ │ │ ├── StdDescriptors.h
│ │ │ │ │ ├── StdRequestType.h
│ │ │ │ │ ├── StreamCallbacks.h
│ │ │ │ │ ├── USBMode.h
│ │ │ │ │ ├── USBTask.c
│ │ │ │ │ └── USBTask.h
│ │ │ │ │ ├── LowLevel
│ │ │ │ │ ├── Device.c
│ │ │ │ │ ├── Device.h
│ │ │ │ │ ├── Endpoint.c
│ │ │ │ │ ├── Endpoint.h
│ │ │ │ │ ├── Host.c
│ │ │ │ │ ├── Host.h
│ │ │ │ │ ├── OTG.h
│ │ │ │ │ ├── Pipe.c
│ │ │ │ │ ├── Pipe.h
│ │ │ │ │ ├── Template
│ │ │ │ │ │ ├── Template_Endpoint_Control_R.c
│ │ │ │ │ │ ├── Template_Endpoint_Control_W.c
│ │ │ │ │ │ ├── Template_Endpoint_RW.c
│ │ │ │ │ │ └── Template_Pipe_RW.c
│ │ │ │ │ ├── USBController.c
│ │ │ │ │ ├── USBController.h
│ │ │ │ │ ├── USBInterrupt.c
│ │ │ │ │ └── USBInterrupt.h
│ │ │ │ │ └── USB.h
│ │ │ ├── License.txt
│ │ │ ├── ManPages
│ │ │ │ ├── AboutLUFA.txt
│ │ │ │ ├── AlternativeStacks.txt
│ │ │ │ ├── BuildingLinkableLibraries.txt
│ │ │ │ ├── ChangeLog.txt
│ │ │ │ ├── CompileTimeTokens.txt
│ │ │ │ ├── CompilingApps.txt
│ │ │ │ ├── ConfiguringApps.txt
│ │ │ │ ├── DevelopingWithLUFA.txt
│ │ │ │ ├── DeviceSupport.txt
│ │ │ │ ├── DirectorySummaries.txt
│ │ │ │ ├── Donating.txt
│ │ │ │ ├── FutureChanges.txt
│ │ │ │ ├── GettingStarted.txt
│ │ │ │ ├── Groups.txt
│ │ │ │ ├── LUFAPoweredProjects.txt
│ │ │ │ ├── LUFAvsAtmelStack.txt
│ │ │ │ ├── LibraryApps.txt
│ │ │ │ ├── LibraryResources.txt
│ │ │ │ ├── LicenseInfo.txt
│ │ │ │ ├── MainPage.txt
│ │ │ │ ├── MigrationInformation.txt
│ │ │ │ ├── ProgrammingApps.txt
│ │ │ │ ├── SchedulerOverview.txt
│ │ │ │ ├── SoftwareBootloaderJump.txt
│ │ │ │ ├── VIDAndPIDValues.txt
│ │ │ │ ├── WhyUseLUFA.txt
│ │ │ │ └── WritingBoardDrivers.txt
│ │ │ ├── Scheduler
│ │ │ │ ├── Scheduler.c
│ │ │ │ └── Scheduler.h
│ │ │ ├── Version.h
│ │ │ └── makefile
│ │ ├── Projects
│ │ │ └── arduino-usbserial
│ │ │ │ ├── Arduino-usbserial.c
│ │ │ │ ├── Arduino-usbserial.h
│ │ │ │ ├── Board
│ │ │ │ └── LEDs.h
│ │ │ │ ├── Descriptors.c
│ │ │ │ ├── Descriptors.h
│ │ │ │ ├── Lib
│ │ │ │ └── LightweightRingBuff.h
│ │ │ │ ├── makefile
│ │ │ │ ├── ppm_encoder.txt
│ │ │ │ └── readme.txt
│ │ ├── ppm_encoder.txt
│ │ ├── readme.txt
│ │ └── windows-dfuprogramming.txt
│ ├── Binaries
│ │ └── Hash.txt
│ ├── Libraries
│ │ ├── PPM_Encoder.h
│ │ ├── PPM_Encoder_v3.h
│ │ ├── changelog_v3.txt
│ │ ├── manual_v3.txt
│ │ └── readme.txt
│ ├── WorkBasket
│ │ ├── Experimental
│ │ │ └── PPM_Encoder.h
│ │ ├── Jeti_Duplex
│ │ │ ├── Jeti_telemetry_protocol.pdf
│ │ │ ├── Jetibox
│ │ │ │ ├── JetiBox.cpp
│ │ │ │ └── JetiBox.h
│ │ │ └── readme.txt
│ │ ├── readme.txt
│ │ └── spektrum_to_ppm_encoder
│ │ │ └── spektrum_to_ppm_encoder.pde
│ └── readme.txt
├── ArduPilotMega_demo
│ ├── ArduPilotMega_demo.pde
│ └── Timers.pde
├── ArdupilotMegaPlanner
│ └── readme.md
├── CHDK-Scripts
│ ├── Cannon S100
│ │ ├── 3DR_EAI_S100.lua
│ │ └── S100 Setup.txt
│ ├── Cannon SX260
│ │ ├── 3DR_EAI_SX260.lua
│ │ └── SX260 Setup.txt
│ ├── README.md
│ └── kap_uav.lua
├── CPUInfo
│ ├── CPUInfo.cpp
│ ├── Makefile
│ ├── make.inc
│ ├── output-px4.txt
│ ├── output.txt
│ └── wscript
├── CodeStyle
│ ├── ardupilot-astyle.sh
│ ├── astylerc
│ └── xmlpretty.py
├── Failsafe
│ ├── Failsafe.pde
│ └── Makefile
├── FlightGear
│ ├── FGShim.c
│ ├── MAVLink.xml
│ ├── Makefile
│ └── fgfs
├── Frame_params
│ ├── 3DR_AERO_M.param
│ ├── 3DR_Aero_RTF.param
│ ├── 3DR_Iris+.param
│ ├── 3DR_QUAD_X4_RTF.param
│ ├── 3DR_Rover.param
│ ├── 3DR_Tarot.bgsc
│ ├── 3DR_X8+_RTF.param
│ ├── 3DR_X8-M_RTF.param
│ ├── 3DR_X8_RTF.param
│ ├── 3DR_Y6A_RTF.param
│ ├── 3DR_Y6B_RTF.param
│ ├── Iris with Front Mount Go Pro.param
│ ├── Iris with Tarot Gimbal.param
│ ├── Iris.param
│ ├── Parrot_Bebop.param
│ ├── Parrot_Bebop2.param
│ └── SToRM32-MAVLink.param
├── GIT_Test
│ └── GIT_Success.txt
├── Hello
│ ├── Hello.cpp
│ ├── Makefile
│ ├── make.inc
│ └── wscript
├── Linux_HAL_Essentials
│ ├── RCInput_UART
│ │ └── pic_firmware.asm
│ ├── README.md
│ ├── devicetree
│ │ ├── bbbmini
│ │ │ ├── BB-BBBMINI-00A0.dtbo
│ │ │ ├── BB-BBBMINI-00A0.dts
│ │ │ ├── Makefile
│ │ │ ├── README.md
│ │ │ └── startup.sh
│ │ └── pxf
│ │ │ ├── BB-BONE-PRU-05-00A0.dtbo
│ │ │ ├── BB-BONE-PRU-05-00A0.dts
│ │ │ ├── BB-PXF-01-00A0.dtbo
│ │ │ ├── BB-PXF-01-00A0.dts
│ │ │ ├── BB-SPI0-PXF-01-00A0.dtbo
│ │ │ ├── BB-SPI0-PXF-01-00A0.dts
│ │ │ ├── BB-SPI1-PXF-01-00A0.dtbo
│ │ │ ├── BB-SPI1-PXF-01-00A0.dts
│ │ │ └── Makefile
│ ├── pru
│ │ ├── aiopru
│ │ │ ├── Makefile
│ │ │ ├── README.md
│ │ │ ├── RcAioPRU.p
│ │ │ ├── RcAioPRUTest.c
│ │ │ └── RcAioPRU_bin.h
│ │ ├── pwmpru
│ │ │ ├── Makefile
│ │ │ ├── linux_types.h
│ │ │ ├── lnk-am33xx.cmd
│ │ │ ├── pru_defs.h
│ │ │ ├── prucomm.h
│ │ │ └── pwmpru1.c
│ │ ├── rangefinderpru
│ │ │ ├── AM335x_PRU.cmd
│ │ │ ├── HexUtil_PRU.cmd
│ │ │ ├── Makefile
│ │ │ ├── README.md
│ │ │ ├── pru_ctrl.h
│ │ │ ├── rangefinder.c
│ │ │ ├── rangefinderprudata.bin
│ │ │ └── rangefinderprutext.bin
│ │ └── rcinpru
│ │ │ ├── Makefile
│ │ │ ├── linux_types.h
│ │ │ ├── lnk-am33xx.cmd
│ │ │ ├── pru_defs.h
│ │ │ ├── prucomm.h
│ │ │ └── rcinpru0.c
│ ├── pwmpru1
│ ├── rcinpru0
│ └── startup.sh
├── LogAnalyzer
│ ├── DataflashLog.py
│ ├── LogAnalyzer.py
│ ├── UnitTest.py
│ ├── VehicleType.py
│ ├── example_output.xml
│ ├── examples
│ │ ├── mechanical_fail.log
│ │ ├── nan.log
│ │ ├── robert_lefebvre_octo_PM.log
│ │ ├── tradheli_brownout.log
│ │ └── underpowered.log
│ └── tests
│ │ ├── TestAutotune.py
│ │ ├── TestBrownout.py
│ │ ├── TestCompass.py
│ │ ├── TestDualGyroDrift.py
│ │ ├── TestDupeLogData.py
│ │ ├── TestEmpty.py
│ │ ├── TestEvents.py
│ │ ├── TestGPSGlitch.py
│ │ ├── TestIMUMatch.py
│ │ ├── TestMotorBalance.py
│ │ ├── TestParams.py
│ │ ├── TestPerformance.py
│ │ ├── TestPitchRollCoupling.py
│ │ ├── TestThrust.py
│ │ ├── TestVCC.py
│ │ └── TestVibration.py
├── PPM_decoding
│ ├── PPM_decoding.pde
│ └── Timers.pde
├── PrintVersion.py
├── Replay
│ ├── CheckLogs.py
│ ├── DataFlashFileReader.cpp
│ ├── DataFlashFileReader.h
│ ├── LR_MsgHandler.cpp
│ ├── LR_MsgHandler.h
│ ├── LogReader.cpp
│ ├── LogReader.h
│ ├── Makefile
│ ├── MsgHandler.cpp
│ ├── MsgHandler.h
│ ├── Parameters.h
│ ├── Replay.cpp
│ ├── Replay.h
│ ├── VehicleType.h
│ ├── make.inc
│ ├── plotit.sh
│ └── wscript
├── SerialProxy
│ ├── SerialProxy.sln
│ ├── SerialProxy.suo
│ └── SerialProxy
│ │ ├── Form1.Designer.cs
│ │ ├── Form1.cs
│ │ ├── Form1.resx
│ │ ├── Program.cs
│ │ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ │ ├── SerialProxy.csproj
│ │ ├── SerialProxy.csproj.user
│ │ ├── app.config
│ │ └── bin
│ │ └── Release
│ │ ├── SerialProxy.exe.config
│ │ └── SerialProxy.pdb
├── Xplane
│ ├── X-Plane.pl
│ └── serproxy-0.1.3-3
│ │ ├── README-wiring.txt
│ │ ├── serproxy
│ │ ├── serproxy.cfg
│ │ └── serproxy.cfg copy
├── ardupilotwaf
│ ├── __init__.py
│ ├── ardupilotwaf.py
│ ├── boards.py
│ ├── build_summary.py
│ ├── cmake.py
│ ├── cxx_checks.py
│ ├── gbenchmark.py
│ ├── git_submodule.py
│ ├── gtest.py
│ ├── mavgen.py
│ ├── px4.py
│ ├── px4
│ │ └── cmake
│ │ │ └── configs
│ │ │ ├── nuttx_px4fmu-common_apm.cmake
│ │ │ ├── nuttx_px4fmu-v1_apm.cmake
│ │ │ ├── nuttx_px4fmu-v2_apm.cmake
│ │ │ └── nuttx_px4fmu-v4_apm.cmake
│ ├── static_linking.py
│ └── toolchain.py
├── autotest
│ ├── ArduPlane-Missions
│ │ ├── CMAC-VTOL-ccw.txt
│ │ ├── CMAC-bigloop.txt
│ │ ├── CMAC-toff-loop.txt
│ │ ├── CMAC-turns.txt
│ │ ├── Dalby-OBC2016-fence.txt
│ │ ├── Dalby-OBC2016.txt
│ │ └── KSFO-VTOL.txt
│ ├── ArduPlane.parm
│ ├── CMAC-circuit.txt
│ ├── CMAC-grid.txt
│ ├── CoaxCopter.parm
│ ├── Helicopter.parm
│ ├── README
│ ├── Rover-skid.parm
│ ├── Rover.parm
│ ├── SingleCopter.parm
│ ├── aircraft
│ │ ├── Rascal
│ │ │ ├── Dialogs
│ │ │ │ └── config.xml
│ │ │ ├── Engines
│ │ │ │ ├── 18x8.xml
│ │ │ │ └── Zenoah_G-26A.xml
│ │ │ ├── Models
│ │ │ │ ├── Rascal.rgb
│ │ │ │ ├── Rascal110-000-013.ac
│ │ │ │ ├── Rascal110.xml
│ │ │ │ ├── Trajectory-Marker.ac
│ │ │ │ ├── Trajectory-Marker.xml
│ │ │ │ └── smokeW.xml
│ │ │ ├── README.Rascal
│ │ │ ├── Rascal-keyboard.xml
│ │ │ ├── Rascal-submodels.xml
│ │ │ ├── Rascal.xml
│ │ │ ├── Rascal110-JSBSim-set.xml
│ │ │ ├── Rascal110-splash.rgb
│ │ │ ├── Systems
│ │ │ │ ├── 110-autopilot.xml
│ │ │ │ ├── airdata.nas
│ │ │ │ ├── electrical.xml
│ │ │ │ ├── main.nas
│ │ │ │ └── ugear.nas
│ │ │ ├── reset_CMAC.xml
│ │ │ └── reset_template.xml
│ │ └── arducopter
│ │ │ ├── Engines
│ │ │ ├── a2830-12.xml
│ │ │ └── prop10x4.5.xml
│ │ │ ├── Models
│ │ │ ├── AutoSave_plus_quad.skp
│ │ │ ├── Untitled.ac
│ │ │ ├── Untitled.skp
│ │ │ ├── Y6_test.ac
│ │ │ ├── Y6_test.skp
│ │ │ ├── Y6_test2.skp
│ │ │ ├── _propeller0_.skb
│ │ │ ├── _propeller0_.skp
│ │ │ ├── arducopter.ac
│ │ │ ├── arducopter.xml
│ │ │ ├── plus_quad.ac
│ │ │ ├── plus_quad.skb
│ │ │ ├── plus_quad.skp
│ │ │ ├── plus_quad2.ac
│ │ │ ├── plus_quad2.dae
│ │ │ ├── plus_quad2.skb
│ │ │ ├── plus_quad2.skp
│ │ │ ├── plus_quad2.xml
│ │ │ ├── quad.3ds
│ │ │ ├── quad.skp
│ │ │ └── shareware_output.3ds
│ │ │ ├── README
│ │ │ ├── arducopter-set.xml
│ │ │ ├── arducopter.xml
│ │ │ ├── data
│ │ │ ├── arducopter_half_step.txt
│ │ │ ├── arducopter_step.txt
│ │ │ └── rw_generic_pylon.ac
│ │ │ ├── initfile.xml
│ │ │ ├── plus_quad2-set.xml
│ │ │ ├── plus_quad2.xml
│ │ │ └── quad.nas
│ ├── ap1.txt
│ ├── apm_unit_tests
│ │ ├── dev
│ │ │ ├── arducopter_Loiter.py
│ │ │ ├── arducopter_RTL.py
│ │ │ ├── arducopter_climb_descend.py
│ │ │ └── arducopter_failsafe.py
│ │ ├── examples
│ │ │ └── arducopter_example_level.py
│ │ └── mustpass
│ │ │ ├── arducopter_arm_disarm.py
│ │ │ └── arducopter_takeoff.py
│ ├── apmrover2.py
│ ├── arducopter.py
│ ├── arduplane.py
│ ├── autotest.py
│ ├── common.py
│ ├── copter_AVC2013_mission.txt
│ ├── copter_AVC2013_params.parm
│ ├── copter_glitch_mission.txt
│ ├── copter_mission.txt
│ ├── copter_optflow.parm
│ ├── copter_params.parm
│ ├── copter_rangefinder.parm
│ ├── copter_spline_mission.txt
│ ├── copter_terrain_mission.txt
│ ├── dump_logs.py
│ ├── fakepos.py
│ ├── fg_plane_view.bat
│ ├── fg_plane_view.sh
│ ├── fg_quad_view.bat
│ ├── fg_quad_view.sh
│ ├── firefly.parm
│ ├── jsb_sim
│ │ ├── fgout_template.xml
│ │ ├── rascal_test_template.xml
│ │ └── runsim.py
│ ├── junit.xml
│ ├── locations.txt
│ ├── param_metadata
│ │ ├── emit.py
│ │ ├── htmlemit.py
│ │ ├── param.py
│ │ ├── param_parse.py
│ │ ├── rstemit.py
│ │ ├── wikiemit.py
│ │ └── xmlemit.py
│ ├── plane-elevons.parm
│ ├── plane-vtail.parm
│ ├── plane.parm
│ ├── pysim
│ │ ├── aircraft.py
│ │ ├── fdpexpect.py
│ │ ├── fg_display.py
│ │ ├── iris_ros.py
│ │ ├── rotmat.py
│ │ ├── testwind.py
│ │ └── util.py
│ ├── quadplane-tri.parm
│ ├── quadplane.parm
│ ├── quadplane.py
│ ├── rover1.txt
│ ├── run_in_terminal_window.sh
│ ├── sim_vehicle.py
│ ├── sim_vehicle.sh
│ ├── tri_params.parm
│ ├── web-firmware
│ │ ├── css
│ │ │ └── main.css
│ │ ├── images
│ │ │ ├── 3DR_Radio.jpg
│ │ │ ├── PX4IO.png
│ │ │ ├── antenna-tracker.png
│ │ │ ├── ap_rc.png
│ │ │ ├── bg.png
│ │ │ ├── companion.png
│ │ │ ├── copter.png
│ │ │ ├── logo.png
│ │ │ ├── plane.png
│ │ │ ├── planner.png
│ │ │ ├── rover.png
│ │ │ └── tools.png
│ │ └── index.html
│ ├── web
│ │ ├── css
│ │ │ └── main.css
│ │ └── index.html
│ └── y6_params.parm
├── gittools
│ ├── git-commit-subsystems
│ ├── git-subsystems-split
│ ├── path-libraries.sh
│ └── path-nonlibraries.sh
├── mavproxy_modules
│ ├── README.md
│ ├── lib
│ │ ├── __init__.py
│ │ ├── geodesic_grid.py
│ │ └── magcal_graph_ui.py
│ ├── magcal_graph.py
│ └── sitl_calibration.py
├── scripts
│ ├── add_git_hashes.py
│ ├── build_all.sh
│ ├── build_all_px4.sh
│ ├── build_all_vrbrain.sh
│ ├── build_autotest.sh
│ ├── build_binaries.sh
│ ├── build_ci.sh
│ ├── build_devrelease.sh
│ ├── build_docs.sh
│ ├── build_examples.py
│ ├── build_examples.sh
│ ├── build_parameters.sh
│ ├── build_vrbrain_binaries.sh
│ ├── build_vrbrain_branch_binaries.sh
│ ├── build_vrbrain_project_binaries.sh
│ ├── configure-ci.sh
│ ├── fix_libraries_includes.sh
│ ├── format.sh
│ ├── frame_sizes.py
│ ├── generate-manifest.py
│ ├── install-apt-ci.sh
│ ├── install-prereqs-arch.sh
│ ├── install-prereqs-ubuntu.sh
│ ├── magfit_flashlog.py
│ ├── runfliptest.sh
│ ├── unpack_mp.sh
│ └── update_wiki.py
└── vagrant
│ ├── README.md
│ ├── initvagrant.sh
│ ├── screenrc
│ └── shellinit.sh
├── Vagrantfile
├── benchmarks
└── AP_gbenchmark.h
├── docs
├── README
├── build-apmrover2.sh
├── build-arducopter.sh
├── build-arduplane.sh
├── build-libs.sh
├── config
│ ├── apmrover2
│ ├── arducopter
│ ├── arduplane
│ ├── default
│ └── libraries
└── setup.sh
├── eclipse.cproject
├── eclipse.project
├── libraries
├── AC_AttitudeControl
│ ├── AC_AttitudeControl.cpp
│ ├── AC_AttitudeControl.h
│ ├── AC_AttitudeControl_Heli.cpp
│ ├── AC_AttitudeControl_Heli.h
│ ├── AC_AttitudeControl_Multi.cpp
│ ├── AC_AttitudeControl_Multi.h
│ ├── AC_PosControl.cpp
│ ├── AC_PosControl.h
│ └── ControlMonitor.cpp
├── AC_Fence
│ ├── AC_Fence.cpp
│ ├── AC_Fence.h
│ └── keywords.txt
├── AC_InputManager
│ ├── AC_InputManager.cpp
│ ├── AC_InputManager.h
│ ├── AC_InputManager_Heli.cpp
│ └── AC_InputManager_Heli.h
├── AC_PID
│ ├── AC_HELI_PID.cpp
│ ├── AC_HELI_PID.h
│ ├── AC_P.cpp
│ ├── AC_P.h
│ ├── AC_PID.cpp
│ ├── AC_PID.h
│ ├── AC_PI_2D.cpp
│ ├── AC_PI_2D.h
│ ├── examples
│ │ └── AC_PID_test
│ │ │ ├── AC_PID_test.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── keywords.txt
├── AC_PrecLand
│ ├── AC_PrecLand.cpp
│ ├── AC_PrecLand.h
│ ├── AC_PrecLand_Backend.h
│ ├── AC_PrecLand_Companion.cpp
│ ├── AC_PrecLand_Companion.h
│ ├── AC_PrecLand_IRLock.cpp
│ └── AC_PrecLand_IRLock.h
├── AC_Sprayer
│ ├── AC_Sprayer.cpp
│ └── AC_Sprayer.h
├── AC_WPNav
│ ├── AC_Circle.cpp
│ ├── AC_Circle.h
│ ├── AC_WPNav.cpp
│ ├── AC_WPNav.h
│ └── keywords.txt
├── APM_Control
│ ├── APM_Control.h
│ ├── AP_AutoTune.cpp
│ ├── AP_AutoTune.h
│ ├── AP_PitchController.cpp
│ ├── AP_PitchController.h
│ ├── AP_RollController.cpp
│ ├── AP_RollController.h
│ ├── AP_SteerController.cpp
│ ├── AP_SteerController.h
│ ├── AP_YawController.cpp
│ ├── AP_YawController.h
│ └── TuningGuide.txt
├── APM_OBC
│ ├── APM_OBC.cpp
│ ├── APM_OBC.h
│ └── Failsafe_Board
│ │ ├── Failsafe_Board.pde
│ │ ├── Makefile
│ │ └── nobuild.txt
├── AP_ADC
│ ├── AP_ADC.cpp
│ ├── AP_ADC.h
│ ├── AP_ADC_ADS1115.cpp
│ ├── AP_ADC_ADS1115.h
│ ├── AP_ADC_ADS7844.cpp
│ ├── AP_ADC_ADS7844.h
│ ├── examples
│ │ └── AP_ADC_test
│ │ │ ├── AP_ADC_test.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── keywords.txt
├── AP_ADSB
│ ├── AP_ADSB.cpp
│ └── AP_ADSB.h
├── AP_AHRS
│ ├── AP_AHRS.cpp
│ ├── AP_AHRS.h
│ ├── AP_AHRS_DCM.cpp
│ ├── AP_AHRS_DCM.h
│ ├── AP_AHRS_NavEKF.cpp
│ ├── AP_AHRS_NavEKF.h
│ └── examples
│ │ └── AHRS_Test
│ │ ├── AHRS_Test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── norelax.inoflag
│ │ └── wscript
├── AP_AccelCal
│ ├── AP_AccelCal.cpp
│ ├── AP_AccelCal.h
│ ├── AccelCalibrator.cpp
│ └── AccelCalibrator.h
├── AP_Airspeed
│ ├── AP_Airspeed.cpp
│ ├── AP_Airspeed.h
│ ├── AP_Airspeed_Backend.h
│ ├── AP_Airspeed_I2C.cpp
│ ├── AP_Airspeed_I2C.h
│ ├── AP_Airspeed_PX4.cpp
│ ├── AP_Airspeed_PX4.h
│ ├── AP_Airspeed_analog.cpp
│ ├── AP_Airspeed_analog.h
│ ├── Airspeed_Calibration.cpp
│ ├── examples
│ │ └── Airspeed
│ │ │ ├── Airspeed.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── models
│ │ └── ADS_cal_EKF.m
├── AP_Arming
│ ├── AP_Arming.cpp
│ └── AP_Arming.h
├── AP_Baro
│ ├── AP_Baro.cpp
│ ├── AP_Baro.h
│ ├── AP_Baro_BMP085.cpp
│ ├── AP_Baro_BMP085.h
│ ├── AP_Baro_Backend.cpp
│ ├── AP_Baro_Backend.h
│ ├── AP_Baro_HIL.cpp
│ ├── AP_Baro_HIL.h
│ ├── AP_Baro_MS5611.cpp
│ ├── AP_Baro_MS5611.h
│ ├── AP_Baro_PX4.cpp
│ ├── AP_Baro_PX4.h
│ ├── AP_Baro_QURT.cpp
│ ├── AP_Baro_QURT.h
│ ├── AP_Baro_qflight.cpp
│ ├── AP_Baro_qflight.h
│ └── examples
│ │ └── BARO_generic
│ │ ├── BARO_generic.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
├── AP_BattMonitor
│ ├── AP_BattMonitor.cpp
│ ├── AP_BattMonitor.h
│ ├── AP_BattMonitor_Analog.cpp
│ ├── AP_BattMonitor_Analog.h
│ ├── AP_BattMonitor_Backend.cpp
│ ├── AP_BattMonitor_Backend.h
│ ├── AP_BattMonitor_Bebop.cpp
│ ├── AP_BattMonitor_Bebop.h
│ ├── AP_BattMonitor_SMBus.h
│ ├── AP_BattMonitor_SMBus_I2C.cpp
│ ├── AP_BattMonitor_SMBus_I2C.h
│ ├── AP_BattMonitor_SMBus_PX4.cpp
│ ├── AP_BattMonitor_SMBus_PX4.h
│ └── examples
│ │ └── AP_BattMonitor_test
│ │ ├── AP_BattMonitor_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
├── AP_BoardConfig
│ ├── AP_BoardConfig.cpp
│ └── AP_BoardConfig.h
├── AP_Buffer
│ └── AP_Buffer.h
├── AP_Camera
│ ├── AP_Camera.cpp
│ └── AP_Camera.h
├── AP_Common
│ ├── AP_Common.cpp
│ ├── AP_Common.h
│ ├── AP_Test.h
│ ├── Location.cpp
│ ├── Location.h
│ ├── c++.cpp
│ ├── examples
│ │ └── AP_Common
│ │ │ ├── AP_Common.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ ├── keywords.txt
│ └── missing
│ │ ├── ap_version.h
│ │ ├── cmath
│ │ ├── cstddef
│ │ ├── type_traits
│ │ └── utility
├── AP_Compass
│ ├── AP_Compass.cpp
│ ├── AP_Compass.h
│ ├── AP_Compass_AK8963.cpp
│ ├── AP_Compass_AK8963.h
│ ├── AP_Compass_Backend.cpp
│ ├── AP_Compass_Backend.h
│ ├── AP_Compass_Calibration.cpp
│ ├── AP_Compass_HIL.cpp
│ ├── AP_Compass_HIL.h
│ ├── AP_Compass_HMC5843.cpp
│ ├── AP_Compass_HMC5843.h
│ ├── AP_Compass_LSM303D.cpp
│ ├── AP_Compass_LSM303D.h
│ ├── AP_Compass_LSM9DS1.cpp
│ ├── AP_Compass_LSM9DS1.h
│ ├── AP_Compass_PX4.cpp
│ ├── AP_Compass_PX4.h
│ ├── AP_Compass_QURT.cpp
│ ├── AP_Compass_QURT.h
│ ├── AP_Compass_qflight.cpp
│ ├── AP_Compass_qflight.h
│ ├── CompassCalibrator.cpp
│ ├── CompassCalibrator.h
│ ├── Compass_learn.cpp
│ ├── examples
│ │ └── AP_Compass_test
│ │ │ ├── AP_Compass_test.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── keywords.txt
├── AP_Declination
│ ├── AP_Declination.cpp
│ ├── AP_Declination.h
│ └── examples
│ │ └── AP_Declination_test
│ │ ├── AP_Declination_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
├── AP_EPM
│ ├── AP_EPM.cpp
│ └── AP_EPM.h
├── AP_Frsky_Telem
│ ├── AP_Frsky_Telem.cpp
│ └── AP_Frsky_Telem.h
├── AP_GPS
│ ├── AP_GPS.cpp
│ ├── AP_GPS.h
│ ├── AP_GPS_ERB.cpp
│ ├── AP_GPS_ERB.h
│ ├── AP_GPS_GSOF.cpp
│ ├── AP_GPS_GSOF.h
│ ├── AP_GPS_MTK.cpp
│ ├── AP_GPS_MTK.h
│ ├── AP_GPS_MTK19.cpp
│ ├── AP_GPS_MTK19.h
│ ├── AP_GPS_MTK_Common.h
│ ├── AP_GPS_NMEA.cpp
│ ├── AP_GPS_NMEA.h
│ ├── AP_GPS_PX4.cpp
│ ├── AP_GPS_PX4.h
│ ├── AP_GPS_QURT.cpp
│ ├── AP_GPS_QURT.h
│ ├── AP_GPS_SBF.cpp
│ ├── AP_GPS_SBF.h
│ ├── AP_GPS_SBP.cpp
│ ├── AP_GPS_SBP.h
│ ├── AP_GPS_SIRF.cpp
│ ├── AP_GPS_SIRF.h
│ ├── AP_GPS_UBLOX.cpp
│ ├── AP_GPS_UBLOX.h
│ ├── GPS_Backend.cpp
│ ├── GPS_Backend.h
│ ├── GPS_detect_state.h
│ ├── config
│ │ ├── 3DR-Ublox.txt
│ │ ├── 3DR-Ublox_NEO7.txt
│ │ └── Marco-Ublox_M8N.txt
│ ├── examples
│ │ ├── GPS_AUTO_test
│ │ │ ├── GPS_AUTO_test.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ └── GPS_UBLOX_passthrough
│ │ │ ├── GPS_UBLOX_passthrough.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── tests
│ │ ├── test_gps.cpp
│ │ └── wscript
├── AP_HAL
│ ├── AP_HAL.h
│ ├── AP_HAL_Boards.h
│ ├── AP_HAL_Macros.h
│ ├── AP_HAL_Main.h
│ ├── AP_HAL_Namespace.h
│ ├── AnalogIn.h
│ ├── Device.h
│ ├── GPIO.h
│ ├── HAL.cpp
│ ├── HAL.h
│ ├── I2CDevice.h
│ ├── I2CDriver.h
│ ├── OpticalFlow.h
│ ├── RCInput.h
│ ├── RCOutput.h
│ ├── SPIDevice.h
│ ├── SPIDriver.h
│ ├── Scheduler.h
│ ├── Semaphores.h
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── Util.cpp
│ ├── Util.h
│ ├── examples
│ │ ├── AnalogIn
│ │ │ ├── AnalogIn.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── nobuild.txt
│ │ │ └── wscript
│ │ ├── Printf
│ │ │ ├── Makefile
│ │ │ ├── Printf.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── RCInput
│ │ │ ├── Makefile
│ │ │ ├── RCInput.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── RCInputToRCOutput
│ │ │ ├── Makefile
│ │ │ ├── RCInputToRCOutput.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── RCOutput
│ │ │ ├── Makefile
│ │ │ ├── RCOutput.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── RCOutput2
│ │ │ ├── Makefile
│ │ │ ├── RCOutput.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── Storage
│ │ │ ├── Makefile
│ │ │ ├── Storage.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ └── UART_test
│ │ │ ├── Makefile
│ │ │ ├── UART_test.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ ├── system.h
│ └── utility
│ │ ├── BetterStream.h
│ │ ├── OwnPtr.h
│ │ ├── Print.cpp
│ │ ├── Print.h
│ │ ├── RingBuffer.cpp
│ │ ├── RingBuffer.h
│ │ ├── Socket.cpp
│ │ ├── Socket.h
│ │ ├── Stream.h
│ │ ├── dsm.cpp
│ │ ├── dsm.h
│ │ ├── ftoa_engine.cpp
│ │ ├── ftoa_engine.h
│ │ ├── functor.h
│ │ ├── getopt_cpp.cpp
│ │ ├── getopt_cpp.h
│ │ ├── print_vprintf.cpp
│ │ ├── print_vprintf.h
│ │ ├── sparse-endian.h
│ │ ├── tests
│ │ ├── test_own_ptr.cpp
│ │ └── wscript
│ │ ├── utoa_invert.cpp
│ │ └── xtoa_fast.h
├── AP_HAL_AVR
│ └── README.md
├── AP_HAL_Empty
│ ├── AP_HAL_Empty.h
│ ├── AP_HAL_Empty_Namespace.h
│ ├── AP_HAL_Empty_Private.h
│ ├── AnalogIn.cpp
│ ├── AnalogIn.h
│ ├── GPIO.cpp
│ ├── GPIO.h
│ ├── HAL_Empty_Class.cpp
│ ├── HAL_Empty_Class.h
│ ├── I2CDevice.h
│ ├── I2CDriver.cpp
│ ├── I2CDriver.h
│ ├── OpticalFlow.h
│ ├── PrivateMember.cpp
│ ├── PrivateMember.h
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCOutput.cpp
│ ├── RCOutput.h
│ ├── SPIDevice.h
│ ├── SPIDriver.cpp
│ ├── SPIDriver.h
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Semaphores.cpp
│ ├── Semaphores.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ └── Util.h
├── AP_HAL_FLYMAPLE
│ └── README.md
├── AP_HAL_Linux
│ ├── AP_HAL_Linux.h
│ ├── AP_HAL_Linux_Namespace.h
│ ├── AP_HAL_Linux_Private.h
│ ├── AnalogIn.cpp
│ ├── AnalogIn.h
│ ├── AnalogIn_ADS1115.cpp
│ ├── AnalogIn_ADS1115.h
│ ├── AnalogIn_IIO.cpp
│ ├── AnalogIn_IIO.h
│ ├── AnalogIn_Navio2.cpp
│ ├── AnalogIn_Navio2.h
│ ├── AnalogIn_Raspilot.cpp
│ ├── AnalogIn_Raspilot.h
│ ├── CameraSensor.cpp
│ ├── CameraSensor.h
│ ├── CameraSensor_Mt9v117.cpp
│ ├── CameraSensor_Mt9v117.h
│ ├── CameraSensor_Mt9v117_Patches.cpp
│ ├── ConsoleDevice.cpp
│ ├── ConsoleDevice.h
│ ├── Flow_PX4.cpp
│ ├── Flow_PX4.h
│ ├── GPIO.cpp
│ ├── GPIO.h
│ ├── GPIO_BBB.cpp
│ ├── GPIO_BBB.h
│ ├── GPIO_Bebop.cpp
│ ├── GPIO_Bebop.h
│ ├── GPIO_Minnow.cpp
│ ├── GPIO_Minnow.h
│ ├── GPIO_RPI.cpp
│ ├── GPIO_RPI.h
│ ├── GPIO_Sysfs.cpp
│ ├── GPIO_Sysfs.h
│ ├── HAL_Linux_Class.cpp
│ ├── HAL_Linux_Class.h
│ ├── Heat.h
│ ├── Heat_Pwm.cpp
│ ├── Heat_Pwm.h
│ ├── I2CDevice.cpp
│ ├── I2CDevice.h
│ ├── I2CDriver.cpp
│ ├── I2CDriver.h
│ ├── OpticalFlow_Onboard.cpp
│ ├── OpticalFlow_Onboard.h
│ ├── PWM_Sysfs.cpp
│ ├── PWM_Sysfs.h
│ ├── Perf.cpp
│ ├── Perf_Lttng.cpp
│ ├── Perf_Lttng.h
│ ├── Perf_Lttng_TracePoints.h
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCInput_AioPRU.cpp
│ ├── RCInput_AioPRU.h
│ ├── RCInput_DSM.cpp
│ ├── RCInput_DSM.h
│ ├── RCInput_Navio2.cpp
│ ├── RCInput_Navio2.h
│ ├── RCInput_PRU.cpp
│ ├── RCInput_PRU.h
│ ├── RCInput_RPI.cpp
│ ├── RCInput_RPI.h
│ ├── RCInput_Raspilot.cpp
│ ├── RCInput_Raspilot.h
│ ├── RCInput_UART.cpp
│ ├── RCInput_UART.h
│ ├── RCInput_UDP.cpp
│ ├── RCInput_UDP.h
│ ├── RCInput_UDP_Protocol.h
│ ├── RCInput_ZYNQ.cpp
│ ├── RCInput_ZYNQ.h
│ ├── RCOutput_AioPRU.cpp
│ ├── RCOutput_AioPRU.h
│ ├── RCOutput_Bebop.cpp
│ ├── RCOutput_Bebop.h
│ ├── RCOutput_PCA9685.cpp
│ ├── RCOutput_PCA9685.h
│ ├── RCOutput_PRU.cpp
│ ├── RCOutput_PRU.h
│ ├── RCOutput_Raspilot.cpp
│ ├── RCOutput_Raspilot.h
│ ├── RCOutput_Sysfs.cpp
│ ├── RCOutput_Sysfs.h
│ ├── RCOutput_ZYNQ.cpp
│ ├── RCOutput_ZYNQ.h
│ ├── RCOutput_qflight.cpp
│ ├── RCOutput_qflight.h
│ ├── RPIOUARTDriver.cpp
│ ├── RPIOUARTDriver.h
│ ├── SPIDevice.cpp
│ ├── SPIDevice.h
│ ├── SPIDriver.cpp
│ ├── SPIDriver.h
│ ├── SPIUARTDriver.cpp
│ ├── SPIUARTDriver.h
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Semaphores.cpp
│ ├── Semaphores.h
│ ├── SerialDevice.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── Storage_FRAM.cpp
│ ├── Storage_FRAM.h
│ ├── TCPServerDevice.cpp
│ ├── TCPServerDevice.h
│ ├── Thread.cpp
│ ├── Thread.h
│ ├── ToneAlarm.cpp
│ ├── ToneAlarm.h
│ ├── ToneAlarm_Raspilot.cpp
│ ├── ToneAlarm_Raspilot.h
│ ├── UARTDevice.cpp
│ ├── UARTDevice.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── UARTQFlight.cpp
│ ├── UARTQFlight.h
│ ├── UDPDevice.cpp
│ ├── UDPDevice.h
│ ├── Util.cpp
│ ├── Util.h
│ ├── Util_RPI.cpp
│ ├── Util_RPI.h
│ ├── VideoIn.cpp
│ ├── VideoIn.h
│ ├── benchmarks
│ │ ├── benchmark_videoin.cpp
│ │ └── wscript
│ ├── examples
│ │ ├── BusTest
│ │ │ ├── BusTest.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── nobuild.txt
│ │ │ └── wscript
│ │ └── GPIOTest
│ │ │ ├── GPIOTest.cpp
│ │ │ ├── Makefile
│ │ │ └── make.inc
│ ├── px4io_protocol.h
│ ├── qflight
│ │ ├── README.md
│ │ ├── dsp_functions.cpp
│ │ ├── qflight_buffer.h
│ │ ├── qflight_dsp.idl
│ │ └── qflight_util.h
│ ├── sbus.cpp
│ ├── sbus.h
│ └── system.cpp
├── AP_HAL_PX4
│ ├── AP_HAL_PX4.h
│ ├── AP_HAL_PX4_Namespace.h
│ ├── AnalogIn.cpp
│ ├── AnalogIn.h
│ ├── GPIO.cpp
│ ├── GPIO.h
│ ├── HAL_PX4_Class.cpp
│ ├── HAL_PX4_Class.h
│ ├── I2CDriver.cpp
│ ├── I2CDriver.h
│ ├── NSHShellStream.cpp
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCOutput.cpp
│ ├── RCOutput.h
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Semaphores.cpp
│ ├── Semaphores.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── Util.cpp
│ ├── Util.h
│ ├── examples
│ │ └── simple
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── simple.cpp
│ │ │ └── wscript
│ ├── px4_param.cpp
│ └── system.cpp
├── AP_HAL_QURT
│ ├── AP_HAL_QURT.h
│ ├── AP_HAL_QURT_Main.h
│ ├── AP_HAL_QURT_Namespace.h
│ ├── AP_HAL_QURT_Private.h
│ ├── HAL_QURT_Class.cpp
│ ├── HAL_QURT_Class.h
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCOutput.cpp
│ ├── RCOutput.h
│ ├── README.md
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Semaphores.cpp
│ ├── Semaphores.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── UDPDriver.cpp
│ ├── UDPDriver.h
│ ├── Util.cpp
│ ├── Util.h
│ ├── dsp_main.cpp
│ ├── mainapp
│ │ ├── getifaddrs.cpp
│ │ └── mainapp.cpp
│ ├── qurt_dsp.idl
│ ├── replace.cpp
│ ├── replace.h
│ └── system.cpp
├── AP_HAL_SITL
│ ├── AP_HAL_SITL.h
│ ├── AP_HAL_SITL_Namespace.h
│ ├── AP_HAL_SITL_Private.h
│ ├── AnalogIn.cpp
│ ├── AnalogIn.h
│ ├── HAL_SITL_Class.cpp
│ ├── HAL_SITL_Class.h
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCOutput.cpp
│ ├── RCOutput.h
│ ├── SITL_State.cpp
│ ├── SITL_State.h
│ ├── SITL_cmdline.cpp
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Semaphores.cpp
│ ├── Semaphores.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── Util.h
│ ├── fenv_polyfill.h
│ ├── sitl_barometer.cpp
│ ├── sitl_compass.cpp
│ ├── sitl_gps.cpp
│ ├── sitl_ins.cpp
│ ├── sitl_optical_flow.cpp
│ └── system.cpp
├── AP_HAL_VRBRAIN
│ ├── AP_HAL_VRBRAIN.h
│ ├── AP_HAL_VRBRAIN_Namespace.h
│ ├── AnalogIn.cpp
│ ├── AnalogIn.h
│ ├── GPIO.cpp
│ ├── GPIO.h
│ ├── HAL_VRBRAIN_Class.cpp
│ ├── HAL_VRBRAIN_Class.h
│ ├── RCInput.cpp
│ ├── RCInput.h
│ ├── RCOutput.cpp
│ ├── RCOutput.h
│ ├── Scheduler.cpp
│ ├── Scheduler.h
│ ├── Storage.cpp
│ ├── Storage.h
│ ├── UARTDriver.cpp
│ ├── UARTDriver.h
│ ├── Util.cpp
│ ├── Util.h
│ └── system.cpp
├── AP_IRLock
│ ├── AP_IRLock.h
│ ├── AP_IRLock_PX4.cpp
│ ├── AP_IRLock_PX4.h
│ ├── IRLock.cpp
│ └── IRLock.h
├── AP_InertialNav
│ ├── AP_InertialNav.h
│ ├── AP_InertialNav_NavEKF.cpp
│ └── AP_InertialNav_NavEKF.h
├── AP_InertialSensor
│ ├── AP_InertialSensor.cpp
│ ├── AP_InertialSensor.h
│ ├── AP_InertialSensor_Backend.cpp
│ ├── AP_InertialSensor_Backend.h
│ ├── AP_InertialSensor_HIL.cpp
│ ├── AP_InertialSensor_HIL.h
│ ├── AP_InertialSensor_L3G4200D.cpp
│ ├── AP_InertialSensor_L3G4200D.h
│ ├── AP_InertialSensor_LSM9DS0.cpp
│ ├── AP_InertialSensor_LSM9DS0.h
│ ├── AP_InertialSensor_MPU6000.cpp
│ ├── AP_InertialSensor_MPU6000.h
│ ├── AP_InertialSensor_MPU9250.cpp
│ ├── AP_InertialSensor_MPU9250.h
│ ├── AP_InertialSensor_PX4.cpp
│ ├── AP_InertialSensor_PX4.h
│ ├── AP_InertialSensor_QURT.cpp
│ ├── AP_InertialSensor_QURT.h
│ ├── AP_InertialSensor_SITL.cpp
│ ├── AP_InertialSensor_SITL.h
│ ├── AP_InertialSensor_UserInteract.h
│ ├── AP_InertialSensor_UserInteract_MAVLink.cpp
│ ├── AP_InertialSensor_UserInteract_MAVLink.h
│ ├── AP_InertialSensor_UserInteract_Stream.cpp
│ ├── AP_InertialSensor_UserInteract_Stream.h
│ ├── AP_InertialSensor_qflight.cpp
│ ├── AP_InertialSensor_qflight.h
│ ├── AuxiliaryBus.cpp
│ ├── AuxiliaryBus.h
│ └── examples
│ │ ├── INS_generic
│ │ ├── INS_generic.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
│ │ ├── VibTest
│ │ ├── Makefile
│ │ ├── VibTest.cpp
│ │ ├── make.inc
│ │ └── wscript
│ │ └── coning.py
├── AP_L1_Control
│ ├── AP_L1_Control.cpp
│ ├── AP_L1_Control.h
│ └── keywords.txt
├── AP_LandingGear
│ ├── AP_LandingGear.cpp
│ └── AP_LandingGear.h
├── AP_Math
│ ├── AP_GeodesicGrid.cpp
│ ├── AP_GeodesicGrid.h
│ ├── AP_Math.cpp
│ ├── AP_Math.h
│ ├── benchmarks
│ │ ├── benchmark_geodesic_grid.cpp
│ │ ├── benchmark_matrix.cpp
│ │ └── wscript
│ ├── definitions.h
│ ├── edc.cpp
│ ├── edc.h
│ ├── examples
│ │ ├── eulers
│ │ │ ├── Makefile
│ │ │ ├── eulers.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── location
│ │ │ ├── Makefile
│ │ │ ├── location.cpp
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── matrix_alg
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── matrix_alg.cpp
│ │ │ └── nocore.inoflag
│ │ ├── polygon
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── polygon.cpp
│ │ │ └── wscript
│ │ └── rotations
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── rotations.cpp
│ │ │ └── wscript
│ ├── keywords.txt
│ ├── location.cpp
│ ├── location.h
│ ├── matrix3.cpp
│ ├── matrix3.h
│ ├── matrix_alg.cpp
│ ├── polygon.cpp
│ ├── polygon.h
│ ├── quaternion.cpp
│ ├── quaternion.h
│ ├── rotations.h
│ ├── tests
│ │ ├── math_test.h
│ │ ├── test_geodesic_grid.cpp
│ │ ├── test_math.cpp
│ │ ├── test_matrix3.cpp
│ │ └── wscript
│ ├── tools
│ │ └── geodesic_grid
│ │ │ ├── README.md
│ │ │ ├── geodesic_grid.py
│ │ │ ├── grid.py
│ │ │ ├── icosahedron.py
│ │ │ └── plot.py
│ ├── vector2.cpp
│ ├── vector2.h
│ ├── vector3.cpp
│ ├── vector3.h
│ └── vectorN.h
├── AP_Menu
│ ├── AP_Menu.cpp
│ └── AP_Menu.h
├── AP_Mission
│ ├── AP_Mission.cpp
│ ├── AP_Mission.h
│ └── examples
│ │ └── AP_Mission_test
│ │ ├── AP_Mission_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
├── AP_Motors
│ ├── AP_Motors.h
│ ├── AP_MotorsCoax.cpp
│ ├── AP_MotorsCoax.h
│ ├── AP_MotorsHeli.cpp
│ ├── AP_MotorsHeli.h
│ ├── AP_MotorsHeli_RSC.cpp
│ ├── AP_MotorsHeli_RSC.h
│ ├── AP_MotorsHeli_Single.cpp
│ ├── AP_MotorsHeli_Single.h
│ ├── AP_MotorsHexa.cpp
│ ├── AP_MotorsHexa.h
│ ├── AP_MotorsMatrix.cpp
│ ├── AP_MotorsMatrix.h
│ ├── AP_MotorsMulticopter.cpp
│ ├── AP_MotorsMulticopter.h
│ ├── AP_MotorsOcta.cpp
│ ├── AP_MotorsOcta.h
│ ├── AP_MotorsOctaQuad.cpp
│ ├── AP_MotorsOctaQuad.h
│ ├── AP_MotorsQuad.cpp
│ ├── AP_MotorsQuad.h
│ ├── AP_MotorsSingle.cpp
│ ├── AP_MotorsSingle.h
│ ├── AP_MotorsTri.cpp
│ ├── AP_MotorsTri.h
│ ├── AP_MotorsY6.cpp
│ ├── AP_MotorsY6.h
│ ├── AP_Motors_Class.cpp
│ ├── AP_Motors_Class.h
│ └── examples
│ │ └── AP_Motors_test
│ │ ├── AP_Motors_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── nobuild.txt
│ │ └── wscript
├── AP_Mount
│ ├── AP_Mount.cpp
│ ├── AP_Mount.h
│ ├── AP_Mount_Alexmos.cpp
│ ├── AP_Mount_Alexmos.h
│ ├── AP_Mount_Backend.cpp
│ ├── AP_Mount_Backend.h
│ ├── AP_Mount_SToRM32.cpp
│ ├── AP_Mount_SToRM32.h
│ ├── AP_Mount_SToRM32_serial.cpp
│ ├── AP_Mount_SToRM32_serial.h
│ ├── AP_Mount_Servo.cpp
│ ├── AP_Mount_Servo.h
│ ├── AP_Mount_SoloGimbal.cpp
│ ├── AP_Mount_SoloGimbal.h
│ ├── SoloGimbal.cpp
│ ├── SoloGimbal.h
│ ├── SoloGimbalEKF.cpp
│ ├── SoloGimbalEKF.h
│ ├── SoloGimbal_Parameters.cpp
│ ├── SoloGimbal_Parameters.h
│ └── examples
│ │ └── trivial_AP_Mount
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── trivial_AP_Mount.cpp
│ │ └── wscript
├── AP_NavEKF
│ ├── AP_NavEKF.cpp
│ ├── AP_NavEKF.h
│ ├── AP_NavEKF_core.cpp
│ ├── AP_NavEKF_core.h
│ ├── AP_Nav_Common.h
│ └── Models
│ │ ├── AttErrVecMathExample
│ │ ├── AlignHeading.m
│ │ ├── AlignTilt.m
│ │ ├── FuseMagnetometer.m
│ │ ├── FuseVelocity.m
│ │ ├── GenerateEquations.m
│ │ ├── PlotData.m
│ │ ├── PredictCovariance.m
│ │ ├── PredictStates.m
│ │ ├── RunRealData.m
│ │ ├── RunSyntheticData.m
│ │ ├── calcF.m
│ │ ├── calcH_MAG.m
│ │ ├── calcQ.m
│ │ └── with_initial_alignment.fig
│ │ ├── Common
│ │ ├── ConvertToC.m
│ │ ├── ConvertToM.m
│ │ ├── EulToQuat.m
│ │ ├── NormQuat.m
│ │ ├── OptimiseAlgebra.m
│ │ ├── Quat2Tbn.m
│ │ ├── QuatDivide.m
│ │ ├── QuatMult.m
│ │ ├── QuatToEul.m
│ │ └── RotToQuat.m
│ │ ├── GimbalEstimatorExample
│ │ ├── AlignHeading.m
│ │ ├── AlignTilt.m
│ │ ├── C_code.txt
│ │ ├── FixAutoGenCCode.m
│ │ ├── FuseMagnetometer.m
│ │ ├── FuseVelocity.m
│ │ ├── GenerateEquations.m
│ │ ├── PlotData.m
│ │ ├── PredictCovariance.m
│ │ ├── PredictCovarianceOptimised.m
│ │ ├── PredictStates.m
│ │ ├── RunSimulation.m
│ │ ├── calcEKF.m
│ │ ├── calcF.c
│ │ ├── calcF.cpp
│ │ ├── calcF.m
│ │ ├── calcH_MAG.c
│ │ ├── calcH_MAG.cpp
│ │ ├── calcH_MAG.m
│ │ ├── calcMagAng.m
│ │ ├── calcP.c
│ │ ├── calcP.cpp
│ │ ├── calcP.m
│ │ ├── calcP.txt
│ │ ├── calcQ.c
│ │ ├── calcQ.cpp
│ │ ├── calcQ.m
│ │ ├── calcSF.c
│ │ ├── calcSP.c
│ │ ├── calcTmn.c
│ │ ├── calcTmn.m
│ │ ├── calcTms.c
│ │ └── calcTms.m
│ │ ├── QuaternionMathExample
│ │ ├── FuseMagnetometer.m
│ │ ├── FuseVelocity.m
│ │ ├── GenerateEquations.m
│ │ ├── PlotData.m
│ │ ├── PredictCovariance.m
│ │ ├── PredictStates.m
│ │ ├── RunRealData.m
│ │ ├── calcF.m
│ │ ├── calcG.m
│ │ ├── calcH_MAG.m
│ │ └── calcQ.m
│ │ ├── ReadMe.txt
│ │ └── testData
│ │ ├── fltTest.mat
│ │ └── gndTest.mat
├── AP_NavEKF2
│ ├── AP_NavEKF2.cpp
│ ├── AP_NavEKF2.h
│ ├── AP_NavEKF2_AirDataFusion.cpp
│ ├── AP_NavEKF2_Buffer.h
│ ├── AP_NavEKF2_Control.cpp
│ ├── AP_NavEKF2_MagFusion.cpp
│ ├── AP_NavEKF2_Measurements.cpp
│ ├── AP_NavEKF2_OptFlowFusion.cpp
│ ├── AP_NavEKF2_Outputs.cpp
│ ├── AP_NavEKF2_PosVelFusion.cpp
│ ├── AP_NavEKF2_VehicleStatus.cpp
│ ├── AP_NavEKF2_core.cpp
│ ├── AP_NavEKF2_core.h
│ └── AP_NavEKF_GyroBias.cpp
├── AP_Navigation
│ └── AP_Navigation.h
├── AP_Notify
│ ├── AP_BoardLED.cpp
│ ├── AP_BoardLED.h
│ ├── AP_Notify.cpp
│ ├── AP_Notify.h
│ ├── Buzzer.cpp
│ ├── Buzzer.h
│ ├── DiscreteRGBLed.cpp
│ ├── DiscreteRGBLed.h
│ ├── Display.cpp
│ ├── Display.h
│ ├── Display_SSD1306_I2C.cpp
│ ├── Display_SSD1306_I2C.h
│ ├── ExternalLED.cpp
│ ├── ExternalLED.h
│ ├── NavioLED.cpp
│ ├── NavioLED.h
│ ├── NavioLED_I2C.cpp
│ ├── NavioLED_I2C.h
│ ├── NotifyDevice.h
│ ├── OreoLED_PX4.cpp
│ ├── OreoLED_PX4.h
│ ├── RCOutputRGBLed.cpp
│ ├── RCOutputRGBLed.h
│ ├── RGBLed.cpp
│ ├── RGBLed.h
│ ├── ToneAlarm_Linux.cpp
│ ├── ToneAlarm_Linux.h
│ ├── ToneAlarm_PX4.cpp
│ ├── ToneAlarm_PX4.h
│ ├── ToneAlarm_PX4_Solo.cpp
│ ├── ToneAlarm_PX4_Solo.h
│ ├── ToshibaLED.cpp
│ ├── ToshibaLED.h
│ ├── ToshibaLED_I2C.cpp
│ ├── ToshibaLED_I2C.h
│ ├── ToshibaLED_PX4.cpp
│ ├── ToshibaLED_PX4.h
│ ├── VRBoard_LED.cpp
│ ├── VRBoard_LED.h
│ └── examples
│ │ ├── AP_Notify_test
│ │ ├── AP_Notify_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── nobuild.txt
│ │ └── wscript
│ │ └── ToshibaLED_test
│ │ ├── Makefile
│ │ ├── ToshibaLED_test.cpp
│ │ ├── make.inc
│ │ └── wscript
├── AP_OpticalFlow
│ ├── AP_OpticalFlow.h
│ ├── AP_OpticalFlow_HIL.cpp
│ ├── AP_OpticalFlow_HIL.h
│ ├── AP_OpticalFlow_Linux.cpp
│ ├── AP_OpticalFlow_Linux.h
│ ├── AP_OpticalFlow_Onboard.cpp
│ ├── AP_OpticalFlow_Onboard.h
│ ├── AP_OpticalFlow_PX4.cpp
│ ├── AP_OpticalFlow_PX4.h
│ ├── OpticalFlow.cpp
│ ├── OpticalFlow.h
│ ├── OpticalFlow_backend.cpp
│ ├── OpticalFlow_backend.h
│ ├── examples
│ │ └── AP_OpticalFlow_test
│ │ │ ├── AP_OpticalFlow_test.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── nobuild.txt
│ │ │ └── wscript
│ └── keywords.txt
├── AP_Parachute
│ ├── AP_Parachute.cpp
│ ├── AP_Parachute.h
│ └── examples
│ │ └── AP_Parachute_test
│ │ ├── AP_Parachute_test.cpp
│ │ ├── make.inc
│ │ └── wscript
├── AP_Param
│ ├── AP_Param.cpp
│ ├── AP_Param.h
│ └── tools
│ │ ├── eedump.c
│ │ ├── eedump.pl
│ │ ├── eedump_apparam.c
│ │ └── eedump_apparam.pl
├── AP_RCMapper
│ ├── AP_RCMapper.cpp
│ └── AP_RCMapper.h
├── AP_RPM
│ ├── AP_RPM.cpp
│ ├── AP_RPM.h
│ ├── RPM_Backend.cpp
│ ├── RPM_Backend.h
│ ├── RPM_PX4_PWM.cpp
│ ├── RPM_PX4_PWM.h
│ ├── RPM_SITL.cpp
│ ├── RPM_SITL.h
│ └── examples
│ │ └── RPM_generic
│ │ ├── Makefile
│ │ ├── RPM_generic.cpp
│ │ ├── make.inc
│ │ └── wscript
├── AP_RSSI
│ ├── AP_RSSI.cpp
│ └── AP_RSSI.h
├── AP_Rally
│ ├── AP_Rally.cpp
│ └── AP_Rally.h
├── AP_RangeFinder
│ ├── AP_RangeFinder.h
│ ├── AP_RangeFinder_BBB_PRU.cpp
│ ├── AP_RangeFinder_BBB_PRU.h
│ ├── AP_RangeFinder_Bebop.cpp
│ ├── AP_RangeFinder_Bebop.h
│ ├── AP_RangeFinder_LightWareI2C.cpp
│ ├── AP_RangeFinder_LightWareI2C.h
│ ├── AP_RangeFinder_LightWareSerial.cpp
│ ├── AP_RangeFinder_LightWareSerial.h
│ ├── AP_RangeFinder_MAVLink.cpp
│ ├── AP_RangeFinder_MAVLink.h
│ ├── AP_RangeFinder_MaxsonarI2CXL.cpp
│ ├── AP_RangeFinder_MaxsonarI2CXL.h
│ ├── AP_RangeFinder_PX4.cpp
│ ├── AP_RangeFinder_PX4.h
│ ├── AP_RangeFinder_PX4_PWM.cpp
│ ├── AP_RangeFinder_PX4_PWM.h
│ ├── AP_RangeFinder_PulsedLightLRF.cpp
│ ├── AP_RangeFinder_PulsedLightLRF.h
│ ├── AP_RangeFinder_analog.cpp
│ ├── AP_RangeFinder_analog.h
│ ├── RangeFinder.cpp
│ ├── RangeFinder.h
│ ├── RangeFinder_Backend.cpp
│ ├── RangeFinder_Backend.h
│ └── examples
│ │ └── RFIND_test
│ │ ├── Makefile
│ │ ├── RFIND_test.cpp
│ │ ├── make.inc
│ │ └── wscript
├── AP_Relay
│ ├── AP_Relay.cpp
│ └── AP_Relay.h
├── AP_Scheduler
│ ├── AP_Scheduler.cpp
│ ├── AP_Scheduler.h
│ └── examples
│ │ └── Scheduler_test
│ │ ├── Makefile
│ │ ├── Scheduler_test.cpp
│ │ ├── make.inc
│ │ └── wscript
├── AP_SerialManager
│ ├── AP_SerialManager.cpp
│ └── AP_SerialManager.h
├── AP_ServoRelayEvents
│ ├── AP_ServoRelayEvents.cpp
│ └── AP_ServoRelayEvents.h
├── AP_SpdHgtControl
│ └── AP_SpdHgtControl.h
├── AP_TECS
│ ├── AP_TECS.cpp
│ └── AP_TECS.h
├── AP_Terrain
│ ├── AP_Terrain.cpp
│ ├── AP_Terrain.h
│ ├── TerrainGCS.cpp
│ ├── TerrainIO.cpp
│ ├── TerrainMission.cpp
│ └── TerrainUtil.cpp
├── AP_Tuning
│ ├── AP_Tuning.cpp
│ └── AP_Tuning.h
├── AP_Vehicle
│ ├── AP_Vehicle.h
│ └── AP_Vehicle_Type.h
├── DataFlash
│ ├── DFMessageWriter.cpp
│ ├── DFMessageWriter.h
│ ├── DataFlash.cpp
│ ├── DataFlash.h
│ ├── DataFlash_Backend.cpp
│ ├── DataFlash_Backend.h
│ ├── DataFlash_Block.cpp
│ ├── DataFlash_Block.h
│ ├── DataFlash_File.cpp
│ ├── DataFlash_File.h
│ ├── DataFlash_MAVLink.cpp
│ ├── DataFlash_MAVLink.h
│ ├── DataFlash_SITL.cpp
│ ├── DataFlash_SITL.h
│ ├── LogFile.cpp
│ ├── LogStructure.h
│ └── examples
│ │ ├── DataFlash_AllTypes
│ │ ├── DataFlash_AllTypes.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ └── wscript
│ │ └── DataFlash_test
│ │ ├── DataFlash_test.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── nobuild.txt
│ │ └── wscript
├── Filter
│ ├── AverageFilter.h
│ ├── Butter.h
│ ├── DerivativeFilter.cpp
│ ├── DerivativeFilter.h
│ ├── Filter.h
│ ├── FilterClass.h
│ ├── FilterWithBuffer.h
│ ├── LeadFilter.cpp
│ ├── LeadFilter.h
│ ├── LowPassFilter.cpp
│ ├── LowPassFilter.h
│ ├── LowPassFilter2p.cpp
│ ├── LowPassFilter2p.h
│ ├── ModeFilter.h
│ ├── examples
│ │ ├── Derivative
│ │ │ ├── Derivative.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── Filter
│ │ │ ├── Filter.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ ├── LowPassFilter
│ │ │ ├── LowPassFilter.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ │ └── LowPassFilter2p
│ │ │ ├── LowPassFilter2p.cpp
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ └── wscript
│ └── keywords.txt
├── GCS_Console
│ ├── GCS_Console.cpp
│ ├── GCS_Console.h
│ └── examples
│ │ └── Console
│ │ ├── Console.cpp
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── nobuild.txt
│ │ ├── simplegcs.cpp
│ │ ├── simplegcs.h
│ │ └── wscript
├── GCS_MAVLink
│ ├── .gitignore
│ ├── GCS.h
│ ├── GCS_Common.cpp
│ ├── GCS_Logs.cpp
│ ├── GCS_MAVLink.cpp
│ ├── GCS_MAVLink.h
│ ├── GCS_Signing.cpp
│ ├── GCS_serial_control.cpp
│ ├── MAVLink_routing.cpp
│ ├── MAVLink_routing.h
│ └── examples
│ │ └── routing
│ │ ├── Makefile
│ │ ├── make.inc
│ │ ├── routing.cpp
│ │ └── wscript
├── PID
│ ├── PID.cpp
│ ├── PID.h
│ ├── examples
│ │ └── pid
│ │ │ ├── Makefile
│ │ │ ├── make.inc
│ │ │ ├── pid.cpp
│ │ │ └── wscript
│ └── keywords.txt
├── RC_Channel
│ ├── RC_Channel.cpp
│ ├── RC_Channel.h
│ ├── RC_Channel_aux.cpp
│ ├── RC_Channel_aux.h
│ └── examples
│ │ ├── RC_Channel
│ │ ├── Makefile
│ │ ├── RC_Channel.cpp
│ │ ├── make.inc
│ │ └── wscript
│ │ └── RC_UART
│ │ ├── Makefile
│ │ ├── RC_UART.cpp
│ │ ├── make.inc
│ │ └── wscript
├── SITL
│ ├── SIM_ADSB.cpp
│ ├── SIM_ADSB.h
│ ├── SIM_Aircraft.cpp
│ ├── SIM_Aircraft.h
│ ├── SIM_Balloon.cpp
│ ├── SIM_Balloon.h
│ ├── SIM_CRRCSim.cpp
│ ├── SIM_CRRCSim.h
│ ├── SIM_Calibration.cpp
│ ├── SIM_Calibration.h
│ ├── SIM_FlightAxis.cpp
│ ├── SIM_FlightAxis.h
│ ├── SIM_Frame.cpp
│ ├── SIM_Frame.h
│ ├── SIM_Gazebo.cpp
│ ├── SIM_Gazebo.h
│ ├── SIM_Gimbal.cpp
│ ├── SIM_Gimbal.h
│ ├── SIM_Helicopter.cpp
│ ├── SIM_Helicopter.h
│ ├── SIM_JSBSim.cpp
│ ├── SIM_JSBSim.h
│ ├── SIM_Motor.cpp
│ ├── SIM_Motor.h
│ ├── SIM_Multicopter.cpp
│ ├── SIM_Multicopter.h
│ ├── SIM_Plane.cpp
│ ├── SIM_Plane.h
│ ├── SIM_QuadPlane.cpp
│ ├── SIM_QuadPlane.h
│ ├── SIM_Rover.cpp
│ ├── SIM_Rover.h
│ ├── SIM_SingleCopter.cpp
│ ├── SIM_SingleCopter.h
│ ├── SIM_Tracker.cpp
│ ├── SIM_Tracker.h
│ ├── SIM_last_letter.cpp
│ ├── SIM_last_letter.h
│ ├── SITL.cpp
│ └── SITL.h
├── StorageManager
│ ├── StorageManager.cpp
│ ├── StorageManager.h
│ └── examples
│ │ └── StorageTest
│ │ ├── Makefile
│ │ ├── StorageTest.cpp
│ │ ├── make.inc
│ │ └── wscript
└── doc
│ ├── Doxyfile
│ └── updateDocs
├── mk
├── PX4
│ ├── ROMFS
│ │ ├── defaults.parm
│ │ ├── firmware
│ │ │ └── oreoled.bin
│ │ ├── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.error
│ │ │ └── rcS
│ │ └── tones
│ │ │ └── startup
│ ├── Tools
│ │ ├── README.md
│ │ ├── gencpp
│ │ │ ├── .gitignore
│ │ │ ├── CHANGELOG.rst
│ │ │ ├── CMakeLists.txt
│ │ │ ├── cmake
│ │ │ │ └── gencpp-extras.cmake.em
│ │ │ ├── package.xml
│ │ │ ├── rosdoc.yaml
│ │ │ ├── scripts
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── gen_cpp.py
│ │ │ │ ├── msg.h.template
│ │ │ │ └── srv.h.template
│ │ │ ├── setup.py
│ │ │ └── src
│ │ │ │ └── gencpp
│ │ │ │ └── __init__.py
│ │ └── genmsg
│ │ │ ├── .gitignore
│ │ │ ├── .hgignore
│ │ │ ├── CHANGELOG.rst
│ │ │ ├── CMakeLists.txt
│ │ │ ├── cmake
│ │ │ ├── genmsg-extras.cmake.em
│ │ │ ├── pkg-genmsg.cmake.em
│ │ │ ├── pkg-genmsg.context.in
│ │ │ ├── pkg-msg-extras.cmake.in
│ │ │ ├── pkg-msg-paths.cmake.develspace.in
│ │ │ └── pkg-msg-paths.cmake.installspace.in
│ │ │ ├── doc
│ │ │ ├── Makefile
│ │ │ ├── conf.py
│ │ │ ├── developer.rst
│ │ │ ├── index.rst
│ │ │ ├── python_api.rst
│ │ │ ├── ros.png
│ │ │ └── usermacros.rst
│ │ │ ├── package.xml
│ │ │ ├── rosdoc.yaml
│ │ │ ├── scripts
│ │ │ └── genmsg_check_deps.py
│ │ │ ├── setup.py
│ │ │ ├── src
│ │ │ └── genmsg
│ │ │ │ ├── __init__.py
│ │ │ │ ├── base.py
│ │ │ │ ├── command_line.py
│ │ │ │ ├── deps.py
│ │ │ │ ├── gentools.py
│ │ │ │ ├── msg_loader.py
│ │ │ │ ├── msgs.py
│ │ │ │ ├── names.py
│ │ │ │ ├── srvs.py
│ │ │ │ └── template_tools.py
│ │ │ └── test
│ │ │ ├── __init__.py
│ │ │ ├── files
│ │ │ ├── geometry_msgs
│ │ │ │ └── msg
│ │ │ │ │ ├── Point.msg
│ │ │ │ │ ├── Point32.msg
│ │ │ │ │ ├── PointStamped.msg
│ │ │ │ │ ├── Polygon.msg
│ │ │ │ │ ├── PolygonStamped.msg
│ │ │ │ │ ├── Pose.msg
│ │ │ │ │ ├── Pose2D.msg
│ │ │ │ │ ├── PoseArray.msg
│ │ │ │ │ ├── PoseStamped.msg
│ │ │ │ │ ├── PoseWithCovariance.msg
│ │ │ │ │ ├── PoseWithCovarianceStamped.msg
│ │ │ │ │ ├── Quaternion.msg
│ │ │ │ │ ├── QuaternionStamped.msg
│ │ │ │ │ ├── Transform.msg
│ │ │ │ │ ├── TransformStamped.msg
│ │ │ │ │ ├── Twist.msg
│ │ │ │ │ ├── TwistStamped.msg
│ │ │ │ │ ├── TwistWithCovariance.msg
│ │ │ │ │ ├── TwistWithCovarianceStamped.msg
│ │ │ │ │ ├── Vector3.msg
│ │ │ │ │ ├── Vector3Stamped.msg
│ │ │ │ │ ├── Wrench.msg
│ │ │ │ │ └── WrenchStamped.msg
│ │ │ ├── invalid
│ │ │ │ └── msg
│ │ │ │ │ ├── BadDepend.msg
│ │ │ │ │ └── BadLocalDepend.msg
│ │ │ ├── rosgraph_msgs
│ │ │ │ └── msg
│ │ │ │ │ ├── Clock.msg
│ │ │ │ │ └── Log.msg
│ │ │ ├── sensor_msgs
│ │ │ │ └── msg
│ │ │ │ │ ├── CameraInfo.msg
│ │ │ │ │ ├── ChannelFloat32.msg
│ │ │ │ │ ├── CompressedImage.msg
│ │ │ │ │ ├── Image.msg
│ │ │ │ │ ├── Imu.msg
│ │ │ │ │ ├── JointState.msg
│ │ │ │ │ ├── Joy.msg
│ │ │ │ │ ├── JoyFeedback.msg
│ │ │ │ │ ├── JoyFeedbackArray.msg
│ │ │ │ │ ├── LaserScan.msg
│ │ │ │ │ ├── NavSatFix.msg
│ │ │ │ │ ├── NavSatStatus.msg
│ │ │ │ │ ├── PointCloud.msg
│ │ │ │ │ ├── PointCloud2.msg
│ │ │ │ │ ├── PointField.msg
│ │ │ │ │ ├── Range.msg
│ │ │ │ │ └── RegionOfInterest.msg
│ │ │ ├── std_msgs
│ │ │ │ └── msg
│ │ │ │ │ ├── Bool.msg
│ │ │ │ │ ├── ColorRGBA.msg
│ │ │ │ │ ├── Duration.msg
│ │ │ │ │ ├── Empty.msg
│ │ │ │ │ ├── Float32.msg
│ │ │ │ │ ├── Float32MultiArray.msg
│ │ │ │ │ ├── Float64.msg
│ │ │ │ │ ├── Float64MultiArray.msg
│ │ │ │ │ ├── Header.msg
│ │ │ │ │ ├── Int16.msg
│ │ │ │ │ ├── Int16MultiArray.msg
│ │ │ │ │ ├── Int32.msg
│ │ │ │ │ ├── Int32MultiArray.msg
│ │ │ │ │ ├── Int64.msg
│ │ │ │ │ ├── Int64MultiArray.msg
│ │ │ │ │ ├── Int8.msg
│ │ │ │ │ ├── Int8MultiArray.msg
│ │ │ │ │ ├── MultiArrayDimension.msg
│ │ │ │ │ ├── MultiArrayLayout.msg
│ │ │ │ │ ├── String.msg
│ │ │ │ │ ├── Time.msg
│ │ │ │ │ ├── UInt16.msg
│ │ │ │ │ ├── UInt16MultiArray.msg
│ │ │ │ │ ├── UInt32.msg
│ │ │ │ │ ├── UInt32MultiArray.msg
│ │ │ │ │ ├── UInt64.msg
│ │ │ │ │ ├── UInt64MultiArray.msg
│ │ │ │ │ ├── UInt8.msg
│ │ │ │ │ └── UInt8MultiArray.msg
│ │ │ ├── std_srvs
│ │ │ │ └── srv
│ │ │ │ │ └── Empty.srv
│ │ │ └── test_ros
│ │ │ │ ├── msg
│ │ │ │ ├── Bad.msg
│ │ │ │ └── TestString.msg
│ │ │ │ └── srv
│ │ │ │ ├── AddTwoInts.srv
│ │ │ │ └── GetPoseStamped.srv
│ │ │ ├── md5tests
│ │ │ ├── different
│ │ │ │ ├── constants1.txt
│ │ │ │ ├── constants2.txt
│ │ │ │ ├── constants3.txt
│ │ │ │ ├── constantsB1.txt
│ │ │ │ ├── constantsB2.txt
│ │ │ │ ├── fields1.txt
│ │ │ │ ├── fields2.txt
│ │ │ │ ├── fields3.txt
│ │ │ │ ├── fields4.txt
│ │ │ │ └── fields5.txt
│ │ │ ├── md5text
│ │ │ │ ├── constant1.txt
│ │ │ │ ├── constant2.txt
│ │ │ │ ├── constant3.txt
│ │ │ │ ├── constantB1.txt
│ │ │ │ ├── constantB2.txt
│ │ │ │ ├── constantC1.txt
│ │ │ │ ├── constantC2.txt
│ │ │ │ ├── embed1.txt
│ │ │ │ ├── embed2.txt
│ │ │ │ ├── embed3.txt
│ │ │ │ ├── embed4.txt
│ │ │ │ ├── empty1.txt
│ │ │ │ ├── empty2.txt
│ │ │ │ ├── empty3.txt
│ │ │ │ ├── empty4.txt
│ │ │ │ ├── field1.txt
│ │ │ │ ├── field2.txt
│ │ │ │ ├── field3.txt
│ │ │ │ ├── field4.txt
│ │ │ │ ├── field5.txt
│ │ │ │ ├── multi1.txt
│ │ │ │ ├── multi2.txt
│ │ │ │ ├── multi3.txt
│ │ │ │ ├── multi4.txt
│ │ │ │ └── multi5.txt
│ │ │ └── same
│ │ │ │ ├── constant1.txt
│ │ │ │ ├── constant2.txt
│ │ │ │ ├── constant3.txt
│ │ │ │ ├── constantB1.txt
│ │ │ │ ├── constantB2.txt
│ │ │ │ ├── constantC1.txt
│ │ │ │ ├── constantC2.txt
│ │ │ │ ├── embed1.txt
│ │ │ │ ├── embed2.txt
│ │ │ │ ├── embed3.txt
│ │ │ │ ├── embed4.txt
│ │ │ │ ├── empty1.txt
│ │ │ │ ├── empty2.txt
│ │ │ │ ├── empty3.txt
│ │ │ │ ├── empty4.txt
│ │ │ │ ├── field1.txt
│ │ │ │ ├── field2.txt
│ │ │ │ ├── field3.txt
│ │ │ │ ├── field4.txt
│ │ │ │ ├── field5.txt
│ │ │ │ ├── multi1.txt
│ │ │ │ ├── multi2.txt
│ │ │ │ ├── multi3.txt
│ │ │ │ ├── multi4.txt
│ │ │ │ └── multi5.txt
│ │ │ ├── test_genmsg_base.py
│ │ │ ├── test_genmsg_command_line.py
│ │ │ ├── test_genmsg_gentools.py
│ │ │ ├── test_genmsg_msg_loader.py
│ │ │ ├── test_genmsg_msgs.py
│ │ │ ├── test_genmsg_names.py
│ │ │ └── test_genmsg_srvs.py
│ ├── bootloader
│ │ ├── README.txt
│ │ ├── px4fmu_bl.bin
│ │ ├── px4fmuv2_bl.bin
│ │ ├── px4fmuv2_bl.elf
│ │ ├── px4fmuv4_bl.bin
│ │ ├── px4io_bl.bin
│ │ └── px4io_bl.elf
│ ├── config_px4fmu-v1_APM.mk
│ ├── config_px4fmu-v2_APM.mk
│ ├── config_px4fmu-v4_APM.mk
│ └── px4_common.mk
├── VRBRAIN
│ ├── ROMFS_VRBRAIN45_APM
│ │ └── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.APMNS
│ │ │ ├── rc.error
│ │ │ └── rcS
│ ├── ROMFS_VRBRAIN51_APM
│ │ └── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.APMNS
│ │ │ ├── rc.error
│ │ │ └── rcS
│ ├── ROMFS_VRBRAIN52_APM
│ │ └── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.APMNS
│ │ │ ├── rc.error
│ │ │ └── rcS
│ ├── ROMFS_VRUBRAIN51_APM
│ │ └── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.APMNS
│ │ │ ├── rc.error
│ │ │ └── rcS
│ ├── ROMFS_VRUBRAIN52_APM
│ │ └── init.d
│ │ │ ├── rc.APM
│ │ │ ├── rc.APMNS
│ │ │ ├── rc.error
│ │ │ └── rcS
│ ├── config_vrbrain-v45P_APM.mk
│ ├── config_vrbrain-v45_APM.mk
│ ├── config_vrbrain-v51P_APM.mk
│ ├── config_vrbrain-v51ProP_APM.mk
│ ├── config_vrbrain-v51Pro_APM.mk
│ ├── config_vrbrain-v51_APM.mk
│ ├── config_vrbrain-v52P_APM.mk
│ ├── config_vrbrain-v52ProP_APM.mk
│ ├── config_vrbrain-v52Pro_APM.mk
│ ├── config_vrbrain-v52_APM.mk
│ ├── config_vrubrain-v51P_APM.mk
│ ├── config_vrubrain-v51_APM.mk
│ ├── config_vrubrain-v52P_APM.mk
│ └── config_vrubrain-v52_APM.mk
├── apm.mk
├── board_linux.mk
├── board_native.mk
├── board_px4.mk
├── board_qflight.mk
├── board_qurt.mk
├── board_vrbrain.mk
├── build_rules.mk
├── check_modules.sh
├── configure.mk
├── environ.mk
├── find_tools.mk
├── help.mk
├── mavgen.mk
├── modules.mk
├── px4_targets.mk
├── sketch_sources.mk
├── targets.mk
├── upload_firmware.mk
└── vrbrain_targets.mk
├── reformat.sh
├── tests
└── AP_gtest.h
├── uncrustify_cpp.cfg
├── uncrustify_headers.cfg
└── wscript
/.gitattributes:
--------------------------------------------------------------------------------
1 |
2 | # bash gets confused if you pass in .sh files from windows
3 | # This breaks Vagrant for some users.
4 | *.sh text eol=lf
5 |
6 |
7 |
--------------------------------------------------------------------------------
/.github/ISSUE_TEMPLATE.md:
--------------------------------------------------------------------------------
1 | #### Issue details
2 | _Please describe the problem, or desired feature_
3 |
4 | #### Version
5 | _What version was the issue encountered with_
6 |
7 | #### Platform
8 | [ ] All
9 | [ ] AntennaTracker
10 | [ ] Copter
11 | [ ] Plane
12 | [ ] Rover
13 |
14 | #### Airframe type
15 | _What type of airframe (flying wing, glider, hex, Y6, octa etc)_
16 |
17 | #### Hardware type
18 | _What autopilot hardware was used? (pixhawk, pixracer, PX4FMU etc)_
19 |
20 | #### Logs
21 | _Please provide a link to any relevant logs that show the issue_
22 |
23 |
--------------------------------------------------------------------------------
/.pydevproject:
--------------------------------------------------------------------------------
1 |
2 |
3 | Default
4 | python 2.7
5 |
6 |
--------------------------------------------------------------------------------
/APMrover2/APM_Config.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | // This file is just a placeholder for your configuration file. If you wish to change any of the setup parameters from
4 | // their default values, place the appropriate #define statements here.
5 |
6 |
7 |
--------------------------------------------------------------------------------
/APMrover2/GCS_Mavlink.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | class GCS_MAVLINK_Rover : public GCS_MAVLINK
6 | {
7 |
8 | public:
9 |
10 | void data_stream_send(void) override;
11 |
12 | protected:
13 |
14 | uint32_t telem_delay() const override;
15 |
16 | private:
17 |
18 | void handleMessage(mavlink_message_t * msg) override;
19 | bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
20 | void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
21 | bool try_send_message(enum ap_message id) override;
22 |
23 | };
24 |
--------------------------------------------------------------------------------
/APMrover2/Makefile:
--------------------------------------------------------------------------------
1 | include ../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/APMrover2/Makefile.waf:
--------------------------------------------------------------------------------
1 | all:
2 | @$(MAKE) -C ../ -f Makefile.waf rover
3 |
--------------------------------------------------------------------------------
/APMrover2/Parameters.pde:
--------------------------------------------------------------------------------
1 | /*
2 | blank file. This is needed to help with upgrades of old versions if MissionPlanner
3 | */
4 |
--------------------------------------------------------------------------------
/APMrover2/capabilities.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Rover.h"
4 |
5 | void Rover::init_capabilities(void)
6 | {
7 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
8 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
9 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT);
10 | }
11 |
--------------------------------------------------------------------------------
/APMrover2/commands_process.cpp:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Rover.h"
4 |
5 | // called by update navigation at 10Hz
6 | // --------------------
7 | void Rover::update_commands(void)
8 | {
9 | if(control_mode == AUTO) {
10 | if (home_is_set != HOME_UNSET && mission.num_commands() > 1) {
11 | mission.update();
12 | }
13 | }
14 | }
15 |
--------------------------------------------------------------------------------
/APMrover2/compat.cpp:
--------------------------------------------------------------------------------
1 | #include "Rover.h"
2 |
3 | void Rover::delay(uint32_t ms)
4 | {
5 | hal.scheduler->delay(ms);
6 | }
7 |
8 | void Rover::mavlink_delay(uint32_t ms)
9 | {
10 | hal.scheduler->delay(ms);
11 | }
12 |
--------------------------------------------------------------------------------
/APMrover2/compat.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #define HIGH 1
4 | #define LOW 0
5 |
--------------------------------------------------------------------------------
/APMrover2/events.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Rover.h"
4 |
5 | void Rover::update_events(void)
6 | {
7 | ServoRelayEvents.update_events();
8 | }
9 |
--------------------------------------------------------------------------------
/APMrover2/version.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "ap_version.h"
4 |
5 | #define THISFIRMWARE "ArduRover v3.0.1"
6 | #define FIRMWARE_VERSION 3,0,1,FIRMWARE_VERSION_TYPE_OFFICIAL
7 |
8 | #ifndef GIT_VERSION
9 | #define FIRMWARE_STRING THISFIRMWARE
10 | #else
11 | #define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
12 | #endif
13 |
--------------------------------------------------------------------------------
/AntennaTracker/APM_Config.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | // This file is just a placeholder for your configuration file. If
4 | // you wish to change any of the setup parameters from their default
5 | // values, place the appropriate #define statements here.
6 |
--------------------------------------------------------------------------------
/AntennaTracker/Makefile:
--------------------------------------------------------------------------------
1 | include ../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/AntennaTracker/Parameters.pde:
--------------------------------------------------------------------------------
1 | /*
2 | blank file. This is needed to help with upgrades of old versions if MissionPlanner
3 | */
4 |
--------------------------------------------------------------------------------
/AntennaTracker/capabilities.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Tracker.h"
4 |
5 | void Tracker::init_capabilities(void)
6 | {
7 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
8 | }
9 |
--------------------------------------------------------------------------------
/AntennaTracker/radio.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Tracker.h"
4 |
5 | // Functions to read the RC radio input
6 |
7 | void Tracker::read_radio()
8 | {
9 | if (hal.rcin->new_input()) {
10 | channel_yaw.set_pwm(hal.rcin->read(CH_YAW));
11 | channel_pitch.set_pwm(hal.rcin->read(CH_PITCH));
12 | }
13 | }
14 |
--------------------------------------------------------------------------------
/AntennaTracker/version.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "ap_version.h"
4 |
5 | #define THISFIRMWARE "AntennaTracker V0.7.8"
6 | #define FIRMWARE_VERSION 0,7,8,FIRMWARE_VERSION_TYPE_DEV
7 |
8 | #ifndef GIT_VERSION
9 | #define FIRMWARE_STRING THISFIRMWARE
10 | #else
11 | #define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
12 | #endif
13 |
--------------------------------------------------------------------------------
/AntennaTracker/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | vehicle = bld.path.name
6 | bld.ap_stlib(
7 | name=vehicle + '_libs',
8 | vehicle=vehicle,
9 | libraries=bld.ap_common_vehicle_libraries() + [
10 | 'PID',
11 | ],
12 | use='mavlink',
13 | )
14 |
15 | bld.ap_program(
16 | program_name='antennatracker',
17 | program_groups=['bin', 'antennatracker'],
18 | use=vehicle + '_libs',
19 | )
20 |
--------------------------------------------------------------------------------
/ArduCopter/.gitignore:
--------------------------------------------------------------------------------
1 | arducopter.cpp
2 |
--------------------------------------------------------------------------------
/ArduCopter/GCS_Mavlink.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | class GCS_MAVLINK_Copter : public GCS_MAVLINK
6 | {
7 |
8 | public:
9 |
10 | void data_stream_send(void) override;
11 |
12 | protected:
13 |
14 | uint32_t telem_delay() const override;
15 |
16 | private:
17 |
18 | void handleMessage(mavlink_message_t * msg) override;
19 | bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
20 | void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
21 | bool try_send_message(enum ap_message id) override;
22 |
23 | };
24 |
--------------------------------------------------------------------------------
/ArduCopter/Makefile:
--------------------------------------------------------------------------------
1 | include ../mk/apm.mk
2 |
3 |
--------------------------------------------------------------------------------
/ArduCopter/Makefile.waf:
--------------------------------------------------------------------------------
1 | all:
2 | @$(MAKE) -C ../ -f Makefile.waf copter
3 |
--------------------------------------------------------------------------------
/ArduCopter/Parameters.pde:
--------------------------------------------------------------------------------
1 | /*
2 | blank file. This is needed to help with upgrades of old versions if MissionPlanner
3 | */
4 |
--------------------------------------------------------------------------------
/ArduCopter/UserVariables.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | // user defined variables
4 |
5 | // example variables used in Wii camera testing - replace with your own
6 | // variables
7 | #ifdef USERHOOK_VARIABLES
8 |
9 | #if WII_CAMERA == 1
10 | WiiCamera ircam;
11 | int WiiRange=0;
12 | int WiiRotation=0;
13 | int WiiDisplacementX=0;
14 | int WiiDisplacementY=0;
15 | #endif // WII_CAMERA
16 |
17 | #endif // USERHOOK_VARIABLES
18 |
19 |
20 |
--------------------------------------------------------------------------------
/ArduCopter/compat.cpp:
--------------------------------------------------------------------------------
1 | #include "Copter.h"
2 |
3 | void Copter::delay(uint32_t ms)
4 | {
5 | hal.scheduler->delay(ms);
6 | }
7 |
--------------------------------------------------------------------------------
/ArduCopter/leds.cpp:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Copter.h"
4 |
5 |
6 | // updates the status of notify
7 | // should be called at 50hz
8 | void Copter::update_notify()
9 | {
10 | notify.update();
11 | }
12 |
13 |
--------------------------------------------------------------------------------
/ArduCopter/version.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "ap_version.h"
4 |
5 | #ifdef GIT_TAG
6 | #define THISFIRMWARE "APM:Copter " GIT_TAG
7 | #else
8 | #define THISFIRMWARE "APM:Copter V3.4-dev"
9 | #endif
10 |
11 | #define FIRMWARE_VERSION 3,4,0,FIRMWARE_VERSION_TYPE_DEV
12 |
13 | #ifndef GIT_VERSION
14 | #define FIRMWARE_STRING THISFIRMWARE
15 | #else
16 | #define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
17 | #endif
18 |
--------------------------------------------------------------------------------
/ArduPlane/APM_Config.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | // This file is just a placeholder for your configuration file. If
4 | // you wish to change any of the setup parameters from their default
5 | // values, place the appropriate #define statements here.
6 |
7 | // If you used to define your CONFIG_APM_HARDWARE setting here, it is no
8 | // longer valid! You should switch to using CONFIG_HAL_BOARD via the HAL_BOARD
9 | // flag in your local config.mk instead.
10 |
11 |
--------------------------------------------------------------------------------
/ArduPlane/GCS_Mavlink.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | class GCS_MAVLINK_Plane : public GCS_MAVLINK
6 | {
7 |
8 | public:
9 |
10 | void data_stream_send(void) override;
11 |
12 | protected:
13 |
14 | uint32_t telem_delay() const override;
15 |
16 | private:
17 |
18 | void handleMessage(mavlink_message_t * msg) override;
19 | bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
20 | void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
21 | bool try_send_message(enum ap_message id) override;
22 |
23 | };
24 |
--------------------------------------------------------------------------------
/ArduPlane/Makefile:
--------------------------------------------------------------------------------
1 | include ../mk/apm.mk
2 |
3 |
--------------------------------------------------------------------------------
/ArduPlane/Makefile.waf:
--------------------------------------------------------------------------------
1 | all:
2 | @$(MAKE) -C ../ -f Makefile.waf plane
3 |
--------------------------------------------------------------------------------
/ArduPlane/Parameters.pde:
--------------------------------------------------------------------------------
1 | /*
2 | blank file. This is needed to help with upgrades of old versions if MissionPlanner
3 | */
4 |
--------------------------------------------------------------------------------
/ArduPlane/capabilities.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "Plane.h"
4 |
5 | void Plane::init_capabilities(void)
6 | {
7 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
8 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
9 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_COMMAND_INT);
10 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT);
11 | hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT);
12 |
13 | }
14 |
--------------------------------------------------------------------------------
/ArduPlane/version.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "ap_version.h"
4 |
5 | #define THISFIRMWARE "ArduPlane V3.6.0"
6 | #define FIRMWARE_VERSION 3,6,0,FIRMWARE_VERSION_TYPE_OFFICIAL
7 |
8 | #ifndef GIT_VERSION
9 | #define FIRMWARE_STRING THISFIRMWARE
10 | #else
11 | #define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
12 | #endif
13 |
--------------------------------------------------------------------------------
/Makefile:
--------------------------------------------------------------------------------
1 | # top level makefile to build SITL for primary vehicle targets.
2 | # Useful for static analysis tools
3 |
4 | all: sitl
5 |
6 | sitl: TARGET=sitl
7 | sitl: plane copter rover antennatracker
8 |
9 | linux: TARGET=linux
10 | linux: plane copter rover antennatracker
11 |
12 | clean: TARGET=clean
13 | clean: plane copter rover antennatracker
14 |
15 | .PHONY: plane copter rover antennatracker
16 |
17 | plane:
18 | $(MAKE) -C ArduPlane $(TARGET)
19 |
20 | copter:
21 | $(MAKE) -C ArduCopter $(TARGET)
22 |
23 | rover:
24 | $(MAKE) -C APMrover2 $(TARGET)
25 |
26 | antennatracker:
27 | $(MAKE) -C AntennaTracker $(TARGET)
28 |
--------------------------------------------------------------------------------
/Tools/APM2_2560_bootloader/FLASH.txt:
--------------------------------------------------------------------------------
1 |
2 | to build the hex:
3 |
4 | make mega2560
5 |
6 | To flash the firmware, use avrdude version 5.11 or above
7 |
8 | SERIAL_PORT=/dev/tty.usbserial
9 |
10 | # erase the chip (necessary before unlocking can happen), then unlock the boot loader area
11 | avrdude -e -c stk500v2 -p m2560 -P $SERIAL_PORT -U lock:w:0x3f:m
12 |
13 | # flash the hex file (whatever.hex)
14 | avrdude -v -c stk500v2 -p m2560 -P $SERIAL_PORT -U flash:w:stk500boot_v2_mega2560.hex
15 |
16 | # re-lock the bootloader area of the chip
17 | avrdude -c stk500v2 -p m2560 -P $SERIAL_PORT -U lock:w:0x0f:m
18 |
--------------------------------------------------------------------------------
/Tools/APM2_2560_bootloader/Makefile:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/APM2_2560_bootloader/Makefile
--------------------------------------------------------------------------------
/Tools/APM_radio_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega328p/readme.txt:
--------------------------------------------------------------------------------
1 |
2 | This is the second generation ppm encoder code designed for APM v1.x boards using ATMega328P.
3 |
4 |
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/makefile:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/makefile
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Bootloaders/arduino-usbdfu/readme.txt:
--------------------------------------------------------------------------------
1 | To setup the project and program an ATMEG32U2 with the Arduino USB DFU bootloader:
2 |
3 |
4 | > make clean
5 | > make
6 | > make program
7 |
8 |
9 |
10 | Check that the board enumerates as "Atmega32u2".
11 | Test by uploading the Arduino-usbserial application firmware (see instructions in Arduino-usbserial directory)
12 |
13 |
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Drivers/amd64/libusb0.sys:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Drivers/amd64/libusb0.sys
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Drivers/atmel_usb_dfu.inf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Drivers/atmel_usb_dfu.inf
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Drivers/ia64/libusb0.sys:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Drivers/ia64/libusb0.sys
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Drivers/x86/libusb0.sys:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Drivers/x86/libusb0.sys
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ChangeLog.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/LUFA/ManPages/ChangeLog.txt
--------------------------------------------------------------------------------
/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/makefile:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/makefile
--------------------------------------------------------------------------------
/Tools/ArduPPM/Binaries/Hash.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/Binaries/Hash.txt
--------------------------------------------------------------------------------
/Tools/ArduPPM/Libraries/readme.txt:
--------------------------------------------------------------------------------
1 |
2 | libraries used by all ArduPPM code bases
--------------------------------------------------------------------------------
/Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jeti_telemetry_protocol.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jeti_telemetry_protocol.pdf
--------------------------------------------------------------------------------
/Tools/ArduPPM/WorkBasket/readme.txt:
--------------------------------------------------------------------------------
1 |
2 | The ArduPPM "Workbasket" is a source of code or tools useful for ppm encoder projects.
3 |
4 |
5 | It is recommanded to delete no more needed stuff when integration in the ArduPPM code has been done to keep the repository size smaller.
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/Tools/ArduPPM/readme.txt:
--------------------------------------------------------------------------------
1 |
2 | ArduPPM is the generic code name for boards or chips responsible for ppm encoding.
3 |
4 |
5 |
6 |
7 | Available firmwares :
8 |
9 |
10 | ATMega328p : second generation ppm encoder code designed for APM v1.x boards using ATMega328P.
11 |
12 |
13 | ATMega32U2 : second generation ppm encoder code designed for boards using ATMega16U2 or ATMega32U2 (PhoneDrone and future APM boards).
14 |
15 |
16 |
17 |
18 |
19 |
20 | APM v1.x users are welcome to use the new ppm encoder code (ATMega328p).
21 |
22 | This firmware should solve compatibility or reliability problems that can be seen with "difficult" receivers.
23 |
24 |
--------------------------------------------------------------------------------
/Tools/ArdupilotMegaPlanner/readme.md:
--------------------------------------------------------------------------------
1 | Mission Planner source code has moved.
2 |
3 | Please goto
4 | https://github.com/ArduPilot/MissionPlanner
5 | or for those git inclined
6 | https://github.com/ArduPilot/MissionPlanner.git
7 |
--------------------------------------------------------------------------------
/Tools/CHDK-Scripts/README.md:
--------------------------------------------------------------------------------
1 | ## 3DR EAI
2 |
3 | Based on: KAP UAV Exposure Control Script v3.1
4 | -- Released under GPL by waterwingz and wayback/peabody
5 | http://chdk.wikia.com/wiki/KAP_%26_UAV_Exposure_Control_Script
--------------------------------------------------------------------------------
/Tools/CPUInfo/Makefile:
--------------------------------------------------------------------------------
1 | #
2 | # Trivial makefile for building APM
3 | #
4 | include ../../mk/apm.mk
5 |
--------------------------------------------------------------------------------
/Tools/CPUInfo/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_program(
6 | use='ap',
7 | program_groups='tools',
8 | )
9 |
--------------------------------------------------------------------------------
/Tools/CodeStyle/ardupilot-astyle.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 |
3 | DIR=$(dirname $(readlink -f $0))
4 |
5 | astyle --options="${DIR}"/astylerc $*
6 |
7 |
--------------------------------------------------------------------------------
/Tools/CodeStyle/astylerc:
--------------------------------------------------------------------------------
1 | style=stroustrup
2 | add-brackets
3 | indent=spaces=4
4 | indent-col1-comments
5 | min-conditional-indent=0
6 | suffix=none
7 | lineend=linux
8 | unpad-paren
9 | pad-header
10 |
--------------------------------------------------------------------------------
/Tools/Failsafe/Makefile:
--------------------------------------------------------------------------------
1 | #
2 | # Trivial makefile for building APM
3 | #
4 | include ../../mk/apm.mk
5 |
6 |
--------------------------------------------------------------------------------
/Tools/FlightGear/Makefile:
--------------------------------------------------------------------------------
1 | #!/usr/bin/make
2 | #
3 | # Requires GNU Make
4 | #
5 |
6 | OS := $(shell uname)
7 |
8 | ifeq ($(OS),Darwin)
9 | CC := cc
10 | CFLAGS := -std=c99
11 | LDFLAGS :=
12 | endif
13 |
14 | ifeq ($(OS),Linux)
15 | CC := cc
16 | CFLAGS := -std=c99 -D_XOPEN_SOURCE=600
17 | LDFLAGS := -lpthread -lm
18 | endif
19 |
20 | CFLAGS += -I./GCS_MAVLink/include
21 | SRCS := FGShim.c
22 |
23 | FGShim: $(SRCS)
24 | $(CC) -o $@ $(SRCS) $(CFLAGS) $(LDFLAGS)
25 |
26 |
27 | clean:
28 | rm -f FGShim *~
29 |
--------------------------------------------------------------------------------
/Tools/Frame_params/3DR_Tarot.bgsc:
--------------------------------------------------------------------------------
1 | [PARAMETERS]
2 | ROLL_ACC=120
3 | ROLL_TOTAL=100
4 | ROLL_VEL=150
5 | ROLL_INT=70
6 | PITCH_ACC=80
7 | PITCH_TOTAL=95
8 | PITCH_VEL=80
9 | PITCH_INT=70
10 | ROLL_MAX=44
11 | ROLL_MIN=-44
12 | PITCH_MAX=0
13 | PITCH_MIN=-90
14 | ROLL_SERVO_CENTER=0
15 | PITCH_SERVO_CENTER=0
16 | YAW_SERVO_CENTER=0
17 | ROLL_SERVO_REV=1
18 | PITCH_SERVO_REV=1
19 | ROLL_RC_ACC=50
20 | PITCH_RC_ACC=50
21 | INSTALL_MODE=2
22 | RECEIVER_TYPE=1
23 | INIT_PITCH=0
24 | INIT_ROLL=0
25 | DEFAULT_MODE=2
26 |
--------------------------------------------------------------------------------
/Tools/Frame_params/SToRM32-MAVLink.param:
--------------------------------------------------------------------------------
1 | #NOTE: SToRM32 3-axis gimbal using MAVlink on Telem2, RC6 controls tilt
2 | MNT_ANGMAX_PAN,17999
3 | MNT_ANGMAX_ROL,4500
4 | MNT_ANGMAX_TIL,1000
5 | MNT_ANGMIN_PAN,-18000
6 | MNT_ANGMIN_ROL,-4500
7 | MNT_ANGMIN_TIL,-9000
8 | MNT_RC_IN_TILT,6
9 | MNT_TYPE,4
10 | SERIAL2_BAUD,115
11 | SERIAL2_PROTOCOL,1
--------------------------------------------------------------------------------
/Tools/GIT_Test/GIT_Success.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/GIT_Test/GIT_Success.txt
--------------------------------------------------------------------------------
/Tools/Hello/Hello.cpp:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | /*
4 | simple hello world sketch
5 | Andrew Tridgell September 2011
6 | */
7 |
8 | #include
9 |
10 | const AP_HAL::HAL& hal = AP_HAL::get_HAL();
11 |
12 | void setup()
13 | {
14 | hal.console->println("hello world");
15 | }
16 |
17 | void loop()
18 | {
19 | hal.scheduler->delay(1000);
20 | hal.console->println("*");
21 | }
22 |
23 | AP_HAL_MAIN();
24 |
--------------------------------------------------------------------------------
/Tools/Hello/Makefile:
--------------------------------------------------------------------------------
1 | #
2 | # Trivial makefile for building APM
3 | #
4 | include ../../mk/apm.mk
5 |
--------------------------------------------------------------------------------
/Tools/Hello/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/bbbmini/BB-BBBMINI-00A0.dtbo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/devicetree/bbbmini/BB-BBBMINI-00A0.dtbo
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/bbbmini/Makefile:
--------------------------------------------------------------------------------
1 | all: BB-BBBMINI-00A0.dtbo
2 |
3 | %.dtbo: %.dts
4 | dtc -O dtb -o $@ -b 0 -@ $<
5 |
6 | install:
7 | cp *.dtbo /lib/firmware
8 |
9 | clean:
10 | rm -f *.dtbo
11 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/bbbmini/startup.sh:
--------------------------------------------------------------------------------
1 | if [ "`echo $1`" = "load" ]; then
2 | echo "Loading Capes..."
3 | echo BB-BBBMINI > /sys/devices/bone_capemgr.9/slots
4 | echo am33xx_pwm > /sys/devices/bone_capemgr.9/slots
5 | echo bone_pwm_P8_36 > /sys/devices/bone_capemgr.9/slots
6 | dmesg | grep "SPI"
7 | dmesg | grep "PRU"
8 | cat /sys/devices/bone_capemgr.9/slots
9 | else
10 | echo "Usage:"
11 | echo " ./startup.sh load : to load the capes"
12 | fi
13 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-BONE-PRU-05-00A0.dtbo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-BONE-PRU-05-00A0.dtbo
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-PXF-01-00A0.dtbo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-PXF-01-00A0.dtbo
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-SPI0-PXF-01-00A0.dtbo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-SPI0-PXF-01-00A0.dtbo
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-SPI1-PXF-01-00A0.dtbo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/devicetree/pxf/BB-SPI1-PXF-01-00A0.dtbo
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/devicetree/pxf/Makefile:
--------------------------------------------------------------------------------
1 | all: BB-BONE-PRU-05-00A0.dtbo BB-SPI0-PXF-01-00A0.dtbo BB-SPI1-PXF-01-00A0.dtbo
2 |
3 | %.dtbo: %.dts
4 | dtc -O dtb -o $@ -b 0 -@ $<
5 |
6 | install:
7 | cp *.dtbo /lib/firmware
8 |
9 | clean:
10 | rm -f *.dtbo
11 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/aiopru/Makefile:
--------------------------------------------------------------------------------
1 | RcAioPRU: RcAioPRU.p
2 | pasm -V3 -c RcAioPRU.p
3 |
4 | test: RcAioPRUTest.c
5 | gcc -g -o RcAioPRUTest RcAioPRUTest.c
6 |
7 | clean:
8 | rm RcAioPRU_bin.h RcAioPRUTest
9 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/aiopru/README.md:
--------------------------------------------------------------------------------
1 | # PRU firmware for 12 x PWM output and RC input
2 |
3 | RC AllInOnePRU can be used with BeagleBone Black
4 |
5 | * Written in [PRU Assembly](http://processors.wiki.ti.com/index.php/PRU_Assembly_Reference_Guide)
6 | * 1 channel RCInput with 5ns accuracy
7 | * 12 channel RCOutput with 1us accuracy
8 |
9 | ## Build and install pasm (PRU Assembler)
10 | 1. `git clone https://github.com/beagleboard/am335x_pru_package.git`
11 | 2. `cd am335x_pru_package`
12 | 3. `make`
13 | 4. `sudo make install`
14 |
15 | ## Rebuild RCAioPRU.p
16 | 1. `cd ardupilot/Tools/Linux_HAL_Essentials/pru/aiopru`
17 | 2. `make`
18 |
19 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/pwmpru/linux_types.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | typedef uint8_t __u8;
6 | typedef uint16_t __u16;
7 | typedef uint32_t __u32;
8 | typedef uint64_t __u64;
9 |
10 | typedef uint8_t u8;
11 | typedef uint16_t u16;
12 | typedef uint32_t u32;
13 | typedef uint64_t u64;
14 |
15 | #define __packed __attribute__((packed))
16 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/rangefinderpru/HexUtil_PRU.cmd:
--------------------------------------------------------------------------------
1 | -b
2 | --image
3 |
4 | ROMS {
5 | PAGE 0:
6 | .text: o = 0x0, l = 0x2000, files={rangefinderprutext.bin}
7 | PAGE 1:
8 | .data: o = 0x0, l = 0x2000, files={rangefinderprudata.bin}
9 | }
10 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/rangefinderpru/README.md:
--------------------------------------------------------------------------------
1 | # PRU firmware for HC-SR04 rangefinder
2 |
3 | HC-SR04 driver that can be used with BeagleBone Black
4 |
5 | ## Install PRU C-Compiler
6 | 1. `sudo apt-get update`
7 | 2. `sudo apt-get install ti-pru-cgt-installer`
8 |
9 | ## Rebuild rangefinder.c
10 | 1. `cd ardupilot/Tools/Linux_HAL_Essentials/rangefinderpru/`
11 | 2. `make`
12 |
13 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprutext.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprutext.bin
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pru/rcinpru/linux_types.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | typedef uint8_t __u8;
6 | typedef uint16_t __u16;
7 | typedef uint32_t __u32;
8 | typedef uint64_t __u64;
9 |
10 | typedef uint8_t u8;
11 | typedef uint16_t u16;
12 | typedef uint32_t u32;
13 | typedef uint64_t u64;
14 |
15 | #define __packed __attribute__((packed))
16 |
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/pwmpru1:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/pwmpru1
--------------------------------------------------------------------------------
/Tools/Linux_HAL_Essentials/rcinpru0:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Linux_HAL_Essentials/rcinpru0
--------------------------------------------------------------------------------
/Tools/LogAnalyzer/VehicleType.py:
--------------------------------------------------------------------------------
1 | class VehicleType():
2 | Plane = 17
3 | Copter = 23
4 | Rover = 37
5 |
6 | # these should really be "Plane", "Copter" and "Rover", but many
7 | # things use these values as triggers in their code:
8 | VehicleTypeString = {
9 | 17: "ArduPlane",
10 | 23: "ArduCopter",
11 | 37: "ArduRover"
12 | }
13 |
--------------------------------------------------------------------------------
/Tools/Replay/DataFlashFileReader.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | class DataFlashFileReader
6 | {
7 | public:
8 | bool open_log(const char *logfile);
9 | bool update(char type[5]);
10 |
11 | virtual bool handle_log_format_msg(const struct log_Format &f) = 0;
12 | virtual bool handle_msg(const struct log_Format &f, uint8_t *msg) = 0;
13 |
14 | protected:
15 | int fd = -1;
16 | bool done_format_msgs = false;
17 | virtual void end_format_msgs(void) {}
18 |
19 | #define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE
20 | struct log_Format formats[LOGREADER_MAX_FORMATS] {};
21 | };
22 |
--------------------------------------------------------------------------------
/Tools/Replay/Makefile:
--------------------------------------------------------------------------------
1 | EXTRAFLAGS += "-DMATH_CHECK_INDEXES=1"
2 | include ../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/Tools/Replay/Parameters.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include
5 |
6 | // Global parameter class.
7 | //
8 | class Parameters {
9 | public:
10 | enum {
11 | k_param_dummy,
12 | k_param_barometer,
13 | k_param_ins,
14 | k_param_ahrs,
15 | k_param_airspeed,
16 | k_param_NavEKF,
17 | k_param_NavEKF2,
18 | k_param_compass,
19 | k_param_dataflash
20 | };
21 | AP_Int8 dummy;
22 | };
23 |
24 | extern const AP_Param::Info var_info[];
25 |
--------------------------------------------------------------------------------
/Tools/Replay/VehicleType.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | class VehicleType {
4 | public:
5 | enum vehicle_type {
6 | VEHICLE_UNKNOWN,
7 | VEHICLE_COPTER,
8 | VEHICLE_PLANE,
9 | VEHICLE_ROVER
10 | };
11 | };
12 |
--------------------------------------------------------------------------------
/Tools/Replay/plotit.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 |
3 | cmd="plot "
4 | echo $#
5 | while [ $# -gt 1 ]; do
6 | if [[ "$1" == *.* ]]; then
7 | cmd="$cmd 'plot.dat' using 1:'$1',"
8 | else
9 | cmd="$cmd 'plot2.dat' using 1:'$1',"
10 | fi
11 | shift
12 | done
13 | if [[ "$1" == *.* ]]; then
14 | cmd="$cmd 'plot.dat' using 1:'$1'"
15 | else
16 | cmd="$cmd 'plot2.dat' using 1:'$1'"
17 | fi
18 | echo $cmd
19 | cat < _plot.gnu
20 | set style data lines
21 | set xlabel "time(s)"
22 | $cmd
23 | pause -1 "hit return to exit"
24 | EOF
25 | gnuplot _plot.gnu
26 |
27 |
--------------------------------------------------------------------------------
/Tools/Replay/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | import boards
5 |
6 | def build(bld):
7 | if not isinstance(bld.get_board(), boards.linux):
8 | return
9 |
10 | bld.ap_program(
11 | use='ap',
12 | program_groups='tools',
13 | )
14 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy.suo:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/SerialProxy/SerialProxy.suo
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/Program.cs:
--------------------------------------------------------------------------------
1 | using System;
2 | using System.Collections.Generic;
3 | using System.Windows.Forms;
4 |
5 | namespace SerialProxy
6 | {
7 | static class Program
8 | {
9 | ///
10 | /// The main entry point for the application.
11 | ///
12 | [STAThread]
13 | static void Main()
14 | {
15 | Application.EnableVisualStyles();
16 | Application.SetCompatibleTextRenderingDefault(false);
17 | Application.Run(new Form1());
18 | }
19 | }
20 | }
21 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/SerialProxy.csproj.user:
--------------------------------------------------------------------------------
1 |
2 |
3 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/bin/Release/SerialProxy.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/Tools/SerialProxy/SerialProxy/bin/Release/SerialProxy.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/SerialProxy/SerialProxy/bin/Release/SerialProxy.pdb
--------------------------------------------------------------------------------
/Tools/Xplane/serproxy-0.1.3-3/serproxy:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/Xplane/serproxy-0.1.3-3/serproxy
--------------------------------------------------------------------------------
/Tools/ardupilotwaf/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/ardupilotwaf/__init__.py
--------------------------------------------------------------------------------
/Tools/ardupilotwaf/px4/cmake/configs/nuttx_px4fmu-v1_apm.cmake:
--------------------------------------------------------------------------------
1 | include(configs/nuttx_px4fmu-common_apm)
2 |
3 | list(APPEND config_module_list
4 | drivers/boards/px4fmu-v1
5 | drivers/px4io
6 | drivers/px4flow
7 | )
8 |
9 | set(config_io_board
10 | px4io-v1
11 | )
12 |
13 |
--------------------------------------------------------------------------------
/Tools/ardupilotwaf/px4/cmake/configs/nuttx_px4fmu-v2_apm.cmake:
--------------------------------------------------------------------------------
1 | include(configs/nuttx_px4fmu-common_apm)
2 |
3 | list(APPEND config_module_list
4 | drivers/lsm303d
5 | drivers/l3gd20
6 | drivers/mpu9250
7 | drivers/boards/px4fmu-v2
8 | drivers/pwm_input
9 | modules/uavcan
10 | lib/mathlib
11 | drivers/px4io
12 | drivers/px4flow
13 | drivers/oreoled
14 | )
15 |
16 | list(APPEND config_extra_libs
17 | uavcan
18 | uavcan_stm32_driver
19 | )
20 |
21 | set(config_io_board
22 | px4io-v2
23 | )
24 |
--------------------------------------------------------------------------------
/Tools/ardupilotwaf/px4/cmake/configs/nuttx_px4fmu-v4_apm.cmake:
--------------------------------------------------------------------------------
1 | include(configs/nuttx_px4fmu-common_apm)
2 |
3 | list(APPEND config_module_list
4 | drivers/mpu9250
5 | drivers/boards/px4fmu-v4
6 | drivers/pwm_input
7 | modules/uavcan
8 | lib/mathlib
9 | lib/rc
10 | )
11 |
12 | list(APPEND config_extra_libs
13 | uavcan
14 | uavcan_stm32_driver
15 | )
16 |
--------------------------------------------------------------------------------
/Tools/ardupilotwaf/static_linking.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | """
5 | WAF Tool to force programs to be statically linked
6 | """
7 |
8 | from waflib.TaskGen import after_method, feature
9 |
10 | @feature('static_linking')
11 | @after_method('apply_link')
12 | def force_static_linking(self):
13 | env = self.link_task.env
14 | env.STLIB += env.LIB
15 | env.LIB = []
16 | env.STLIB_MARKER = '-static'
17 | env.SHLIB_MARKER = ''
18 |
--------------------------------------------------------------------------------
/Tools/autotest/ArduPlane-Missions/CMAC-bigloop.txt:
--------------------------------------------------------------------------------
1 | QGC WPL 110
2 | 0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.362938 149.165085 584.400024 1
3 | 1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360916 149.162460 99.669998 1
4 | 2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365421 149.163071 98.970001 1
5 | 3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365284 149.164474 99.470001 1
6 | 4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360806 149.163940 98.019997 1
7 | 5 0 3 177 1.000000 -1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
8 | 6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.359272 149.163757 100.000000 1
9 |
--------------------------------------------------------------------------------
/Tools/autotest/ArduPlane-Missions/Dalby-OBC2016-fence.txt:
--------------------------------------------------------------------------------
1 | -27.302433 151.332031
2 | -27.274988 151.340408
3 | -27.266756 151.286957
4 | -27.277533 151.284409
5 | -27.278055 151.286621
6 | -27.298996 151.281708
7 | -27.311651 151.353165
8 | -27.330996 151.370499
9 | -27.332727 151.368820
10 | -27.338106 151.375565
11 | -27.332232 151.382355
12 | -27.325897 151.376236
13 | -27.326691 151.375214
14 | -27.305651 151.356354
15 | -27.294355 151.289230
16 | -27.278963 151.292664
17 | -27.284918 151.338394
18 | -27.274988 151.340408
19 |
--------------------------------------------------------------------------------
/Tools/autotest/README:
--------------------------------------------------------------------------------
1 | This is an automated test suite for APM
2 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Engines/Zenoah_G-26A.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | 2207.27
8 |
9 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Models/Rascal.rgb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/Rascal/Models/Rascal.rgb
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Models/Trajectory-Marker.ac:
--------------------------------------------------------------------------------
1 | AC3Db
2 | MATERIAL "ac3dmat9" rgb 0 0 1 amb 0 0 1 emis 0 0 1 spec 0 0 1 shi 0 trans 0
3 | MATERIAL "ac3dmat3" rgb 1 0 0 amb 1 0 0 emis 1 0 0 spec 1 0 0 shi 0 trans 0
4 | OBJECT world
5 | kids 2
6 | OBJECT poly
7 | name "line"
8 | loc 0 0.5 0
9 | numvert 2
10 | 0 0.5 0
11 | 0 -0.5 0
12 | numsurf 1
13 | SURF 0x22
14 | mat 0
15 | refs 2
16 | 0 0 1
17 | 1 0 0
18 | kids 0
19 | OBJECT poly
20 | name "line"
21 | numvert 2
22 | 0 0 -3
23 | 0 0 3
24 | numsurf 1
25 | SURF 0x22
26 | mat 1
27 | refs 2
28 | 0 0 1
29 | 1 0 0
30 | kids 0
31 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Models/Trajectory-Marker.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | Trajectory-Marker.ac
8 |
9 |
10 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/README.Rascal:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/Rascal/README.Rascal
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Rascal-keyboard.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 | Ctrl-I
7 | Show configuration dialog
8 |
9 | nasal
10 |
11 |
12 |
13 |
14 |
15 | S
16 | Toggle smoke
17 |
18 | property-toggle
19 | sim/multiplay/generic/int[0]
20 |
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Rascal110-splash.rgb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/Rascal/Rascal110-splash.rgb
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/Systems/main.nas:
--------------------------------------------------------------------------------
1 | var dialog = gui.Dialog.new("/sim/gui/dialogs/rascal/config/dialog",
2 | "Aircraft/Rascal/Dialogs/config.xml");
3 |
4 | var last_time = 0.0;
5 |
6 |
7 | var main_loop = func {
8 | var time = getprop("/sim/time/elapsed-sec");
9 | var dt = time - last_time;
10 | last_time = time;
11 |
12 | update_airdata( dt );
13 | update_vars( dt );
14 | update_ugear( dt );
15 |
16 | settimer(main_loop, 0);
17 | }
18 |
19 |
20 | setlistener("/sim/signals/fdm-initialized",
21 | func {
22 | main_loop();
23 | });
24 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/reset_CMAC.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | -35.362851
4 | 149.165223
5 | 0
6 | 0.0
7 | 0.0
8 | 0.0
9 | 0.0
10 | 0.0
11 |
12 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/Rascal/reset_template.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | %(LATITUDE)s
4 | %(LONGITUDE)s
5 | 1.3
6 | 0.0
7 | 0.0
8 | 0.0
9 | 13.0
10 | %(HEADING)s
11 |
12 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Engines/a2830-12.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | 187
4 |
5 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/AutoSave_plus_quad.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/AutoSave_plus_quad.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/Untitled.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/Untitled.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/Y6_test.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/Y6_test.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/Y6_test2.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/Y6_test2.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/_propeller0_.skb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/_propeller0_.skb
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/_propeller0_.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/_propeller0_.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/plus_quad.skb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/plus_quad.skb
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/plus_quad.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/plus_quad.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/plus_quad2.skb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/plus_quad2.skb
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/plus_quad2.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/plus_quad2.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/quad.3ds:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/quad.3ds
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/quad.skp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/quad.skp
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/Models/shareware_output.3ds:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/aircraft/arducopter/Models/shareware_output.3ds
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/README:
--------------------------------------------------------------------------------
1 | This model is based on the arducopter mode from James Goppert, and
2 | adapted for use in the ArduPilot test system. Many thanks to all who
3 | have contributed!
4 |
--------------------------------------------------------------------------------
/Tools/autotest/aircraft/arducopter/initfile.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | nan
4 | nan
5 | nan
6 | nan
7 | -nan
8 | nan
9 | nan
10 | nan
11 | nan
12 |
13 |
--------------------------------------------------------------------------------
/Tools/autotest/ap1.txt:
--------------------------------------------------------------------------------
1 | QGC WPL 110
2 | 0 1 0 16 0 0 0 0 -35.362881 149.165222 582.000000 1
3 | 1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361553 149.163956 100.000000 1
4 | 2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364540 149.162857 100.000000 1
5 | 3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361721 149.161835 40.000000 1
6 | 4 0 3 178 0.000000 13.00000 0.000000 0.000000 0.000000 0.000000 15.000000 1
7 | 5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.367970 149.164124 28.000000 1
8 | 6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366814 149.165878 28.000000 1
9 | 7 0 3 21 0.000000 0.000000 0.000000 0.000000 -35.362911 149.165222 0.000000 1
10 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/dev/arducopter_Loiter.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510) and
9 | arducopter.hover(mavproxy,mav, hover_throttle=1300) and
10 | arducopter.loiter(mavproxy, mav, holdtime=45, maxaltchange=20)): # 45 second loiter
11 | return True
12 | return False
13 |
14 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/dev/arducopter_RTL.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.takeoff(mavproxy,mav, alt_min=80, takeoff_throttle=1510) and
9 | arducopter.hover(mavproxy,mav, hover_throttle=1300) and
10 | arducopter.fly_RTL(mavproxy, mav, side=80, timeout=80)):
11 | return True
12 | return False
13 |
14 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/dev/arducopter_climb_descend.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510) and
9 | arducopter.change_alt(mavproxy, mav, alt_min=60) and
10 | arducopter.change_alt(mavproxy, mav, alt_min=20)
11 | ):
12 | return True
13 | return False
14 |
15 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/dev/arducopter_failsafe.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.takeoff(mavproxy,mav, alt_min=80, takeoff_throttle=1510) and
9 | arducopter.hover(mavproxy,mav, hover_throttle=1300) and
10 | arducopter.fly_failsafe(mavproxy, mav, side=80, timeout=120)
11 | ):
12 | return True
13 | return False
14 |
15 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/examples/arducopter_example_level.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (arducopter.calibrate_level(mavproxy, mav)):
6 | return True
7 | return False
8 |
9 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/mustpass/arducopter_arm_disarm.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.disarm_motors(mavproxy,mav)):
9 | return True
10 | return False
11 |
12 |
--------------------------------------------------------------------------------
/Tools/autotest/apm_unit_tests/mustpass/arducopter_takeoff.py:
--------------------------------------------------------------------------------
1 | import arducopter
2 |
3 | def unit_test(mavproxy, mav):
4 | '''A scripted flight plan'''
5 | if (
6 | arducopter.calibrate_level(mavproxy, mav) and
7 | arducopter.arm_motors(mavproxy, mav) and
8 | arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510)):
9 | return True
10 | return False
11 |
12 |
--------------------------------------------------------------------------------
/Tools/autotest/copter_glitch_mission.txt:
--------------------------------------------------------------------------------
1 | QGC WPL 110
2 | 0 1 0 16 0 0 0 0 -35.362881 149.165222 582.000000 1
3 | 1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20.000000 1
4 | 2 0 3 16 0.000000 3.000000 0.000000 0.000000 -35.364416 149.166355 20.000000 1
5 | 3 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
6 |
--------------------------------------------------------------------------------
/Tools/autotest/copter_optflow.parm:
--------------------------------------------------------------------------------
1 | ARMING_CHECK -33
2 | EKF_GPS_TYPE 3
3 | FLOW_ENABLE 1
4 | RNGFND_TYPE 1
5 | RNGFND_MIN_CM 0
6 | RNGFND_MAX_CM 4000
7 | RNGFND_PIN 0
8 | RNGFND_SCALING 12.12
9 | SIM_FLOW_ENABLE 1
--------------------------------------------------------------------------------
/Tools/autotest/copter_rangefinder.parm:
--------------------------------------------------------------------------------
1 | RNGFND_TYPE 1
2 | RNGFND_MIN_CM 0
3 | RNGFND_MAX_CM 4000
4 | RNGFND_PIN 0
5 | RNGFND_SCALING 12.12
--------------------------------------------------------------------------------
/Tools/autotest/copter_terrain_mission.txt:
--------------------------------------------------------------------------------
1 | QGC WPL 110
2 | 0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 985.000000 1
3 | 1 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 25.000000 1
4 | 2 0 10 16 0.000000 0.000000 0.000000 0.000000 36.319240 138.649993 25.000000 1
5 | 3 0 10 16 0.000000 0.000000 0.000000 0.000000 36.320035 138.660250 25.000000 1
6 | 4 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
7 |
--------------------------------------------------------------------------------
/Tools/autotest/jsb_sim/fgout_template.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
--------------------------------------------------------------------------------
/Tools/autotest/junit.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ${{tests:
4 | ${result}
5 | }}
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/Tools/autotest/param_metadata/emit.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | import re
4 | from param import *
5 |
6 | # The standard interface emitters must implement
7 | class Emit:
8 | prog_values_field = re.compile(r"\s*(-?\w+:\w+)+,*")
9 |
10 | def close(self):
11 | pass
12 |
13 | def start_libraries(self):
14 | pass
15 |
16 | def emit(self, g, f):
17 | pass
18 |
19 | def set_annotate_with_vehicle(self, value):
20 | self.annotate_with_vehicle = value
21 |
22 |
--------------------------------------------------------------------------------
/Tools/autotest/pysim/testwind.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # simple test of wind generation code
3 |
4 | import util, time, random
5 | from rotmat import Vector3
6 |
7 | wind = util.Wind('7,90,0.1')
8 |
9 | t0 = time.time()
10 | velocity = Vector3(0,0,0)
11 |
12 | t = 0
13 | deltat = 0.01
14 |
15 | while t < 60:
16 | print("%.4f %f" % (t, wind.drag(velocity, deltat=deltat).length()))
17 | t += deltat
18 |
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/3DR_Radio.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/3DR_Radio.jpg
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/PX4IO.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/PX4IO.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/antenna-tracker.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/antenna-tracker.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/ap_rc.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/ap_rc.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/bg.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/bg.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/companion.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/companion.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/copter.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/copter.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/logo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/logo.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/plane.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/plane.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/planner.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/planner.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/rover.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/rover.png
--------------------------------------------------------------------------------
/Tools/autotest/web-firmware/images/tools.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/autotest/web-firmware/images/tools.png
--------------------------------------------------------------------------------
/Tools/mavproxy_modules/lib/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/Tools/mavproxy_modules/lib/__init__.py
--------------------------------------------------------------------------------
/Tools/scripts/build_all_px4.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | # build all targets for PX4
3 | # This helps when doing large merges
4 | # Andrew Tridgell, February 2013
5 |
6 | . config.mk
7 |
8 | set -e
9 | set -x
10 |
11 | git submodule init
12 | git submodule update
13 |
14 | for d in ArduPlane ArduCopter APMrover2; do
15 | pushd $d
16 | make px4-clean
17 | popd
18 | done
19 |
20 | echo "Testing ArduPlane build"
21 | pushd ArduPlane
22 | make px4
23 | popd
24 |
25 | echo "Testing ArduCopter build"
26 | pushd ArduCopter
27 | make px4
28 | popd
29 |
30 | echo "Testing APMrover2 build"
31 | pushd APMrover2
32 | make px4
33 | popd
34 |
35 | exit 0
36 |
--------------------------------------------------------------------------------
/Tools/scripts/build_all_vrbrain.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | # build all targets for PX4
3 | # This helps when doing large merges
4 | # Andrew Tridgell, February 2013
5 |
6 | . config.mk
7 |
8 | set -e
9 | set -x
10 |
11 | for d in ArduPlane ArduCopter APMrover2; do
12 | pushd $d
13 | make vrbrain-clean
14 | popd
15 | done
16 |
17 | echo "Testing ArduPlane build"
18 | pushd ArduPlane
19 | make vrbrain
20 | popd
21 |
22 | echo "Testing ArduCopter build"
23 | pushd ArduCopter
24 | make vrbrain
25 | popd
26 |
27 | echo "Testing APMrover2 build"
28 | pushd APMrover2
29 | make vrbrain
30 | popd
31 |
32 | exit 0
33 |
--------------------------------------------------------------------------------
/Tools/scripts/build_docs.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 |
3 | set -e
4 |
5 | # work from either APM directory or above
6 | [ -d ArduPlane ] || cd APM
7 |
8 | export DOCS_OUTPUT_BASE=../buildlogs/docs
9 |
10 | (
11 | ./docs/build-libs.sh
12 | ./docs/build-arduplane.sh
13 | ./docs/build-arducopter.sh
14 | ./docs/build-apmrover2.sh
15 | ) > ../buildlogs/build_docs.log 2>&1
16 |
--------------------------------------------------------------------------------
/Tools/scripts/build_examples.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 |
3 | set -e
4 |
5 | cat >&2 < %n%f* %t%{= kG}%+Lw%< %{= kG}%-=%c:%s%{-}'
10 | hardstatus string '%{= kG}[ %{G}%H %{g}][%= %{= kw}%?%-Lw%?%{r}(%{W}%n*%f%t%?(%u)%?%{r})%{w}%?%+Lw%?%?%= %{g}][%{B} %m-%d %{W}%c %{g}]'
--------------------------------------------------------------------------------
/Tools/vagrant/shellinit.sh:
--------------------------------------------------------------------------------
1 | # Init that is run every time a new session starts up
2 |
3 | export APMROOT=/vagrant
4 | export PATH=$APMROOT/Tools/autotest:$PATH
5 |
6 | cd $APMROOT/ArduCopter
7 |
8 | echo "Ardupilot environment ready. Run 'sim_vehicle.sh' to start simulating an arducopter instance."
9 | echo "or run 'make sitl' to just do a test build."
10 |
--------------------------------------------------------------------------------
/docs/README:
--------------------------------------------------------------------------------
1 | You need doxygen and graphviz installed.
2 |
3 | Run the build-libs script first, then the project you're interested in.
4 | HTMl will be generated and placed into docs/projectname.
5 |
--------------------------------------------------------------------------------
/docs/build-apmrover2.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
3 |
4 | cd $DIR/..
5 |
6 | . docs/setup.sh
7 |
8 | if [ ! -f $DOCS_OUTPUT_BASE/tags/libraries ];
9 | then
10 | echo "Must build libraries first"
11 | exit 0
12 | fi
13 |
14 | doxygen docs/config/apmrover2
15 |
16 |
--------------------------------------------------------------------------------
/docs/build-arducopter.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
3 |
4 | cd $DIR/..
5 |
6 | . docs/setup.sh
7 |
8 | if [ ! -f $DOCS_OUTPUT_BASE/tags/libraries ];
9 | then
10 | echo "Must build libraries first"
11 | exit 0
12 | fi
13 |
14 | doxygen docs/config/arducopter
15 |
16 |
--------------------------------------------------------------------------------
/docs/build-arduplane.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
3 |
4 | cd $DIR/..
5 |
6 | . docs/setup.sh
7 |
8 | if [ ! -f $DOCS_OUTPUT_BASE/tags/libraries ];
9 | then
10 | echo "Must build libraries first"
11 | exit 0
12 | fi
13 |
14 | doxygen docs/config/arduplane
15 |
16 |
--------------------------------------------------------------------------------
/docs/build-libs.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
3 |
4 | cd $DIR/..
5 |
6 | . docs/setup.sh
7 |
8 | doxygen docs/config/libraries
9 |
--------------------------------------------------------------------------------
/docs/config/apmrover2:
--------------------------------------------------------------------------------
1 | @INCLUDE = docs/config/default
2 |
3 | PROJECT_NAME = "APM:Rover"
4 | INPUT = APMrover2/
5 | OUTPUT_DIRECTORY = $(DOCS_OUTPUT_BASE)/APMrover2
6 | HTML_OUTPUT = .
7 | TAGFILES = $(DOCS_OUTPUT_BASE)/tags/libraries=../libraries
8 |
9 |
--------------------------------------------------------------------------------
/docs/config/arducopter:
--------------------------------------------------------------------------------
1 | @INCLUDE = docs/config/default
2 |
3 | PROJECT_NAME = "APM:Copter"
4 | INPUT = ArduCopter/
5 | OUTPUT_DIRECTORY = $(DOCS_OUTPUT_BASE)/ArduCopter
6 | HTML_OUTPUT = .
7 | TAGFILES = $(DOCS_OUTPUT_BASE)/tags/libraries=../libraries
8 |
9 |
--------------------------------------------------------------------------------
/docs/config/arduplane:
--------------------------------------------------------------------------------
1 | @INCLUDE = docs/config/default
2 |
3 | PROJECT_NAME = "APM:Plane"
4 | INPUT = ArduPlane/
5 | OUTPUT_DIRECTORY = $(DOCS_OUTPUT_BASE)/ArduPlane
6 | HTML_OUTPUT = .
7 | TAGFILES = $(DOCS_OUTPUT_BASE)/tags/libraries=../libraries
8 |
--------------------------------------------------------------------------------
/docs/config/libraries:
--------------------------------------------------------------------------------
1 | @INCLUDE = docs/config/default
2 |
3 | PROJECT_NAME = "APM:Libraries"
4 | INPUT = libraries/
5 | OUTPUT_DIRECTORY = $(DOCS_OUTPUT_BASE)/libraries
6 | HTML_OUTPUT = .
7 | GENERATE_TAGFILE = $(DOCS_OUTPUT_BASE)/tags/libraries
8 |
--------------------------------------------------------------------------------
/docs/setup.sh:
--------------------------------------------------------------------------------
1 | # setup output directory
2 |
3 | [ -z "$DOCS_OUTPUT_BASE" ] && {
4 | export DOCS_OUTPUT_BASE=docs
5 | }
6 |
7 | mkdir -p $DOCS_OUTPUT_BASE/tags
8 |
9 |
--------------------------------------------------------------------------------
/libraries/AC_Fence/keywords.txt:
--------------------------------------------------------------------------------
1 | AC_Fence KEYWORD1
2 | enable KEYWORD2
3 | enabled KEYWORD2
4 | get_enabled_fences KEYWORD2
5 | pre_arm_check KEYWORD2
6 | check_fence KEYWORD2
7 | get_breaches KEYWORD2
8 | get_breach_time KEYWORD2
9 | get_breach_count KEYWORD2
10 | get_action KEYWORD2
11 | set_home_distance KEYWORD2
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/libraries/AC_InputManager/AC_InputManager.cpp:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | #include "AC_InputManager.h"
4 | #include
5 | #include
6 |
7 | extern const AP_HAL::HAL& hal;
8 |
9 | const AP_Param::GroupInfo AC_InputManager::var_info[] = {
10 |
11 | // Placeholder for future parameters in this class.
12 |
13 | AP_GROUPEND
14 | };
15 |
--------------------------------------------------------------------------------
/libraries/AC_PID/examples/AC_PID_test/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/AC_PID/examples/AC_PID_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AC_PID/keywords.txt:
--------------------------------------------------------------------------------
1 | PID KEYWORD1
2 | get_pid KEYWORD2
3 | reset_I KEYWORD2
4 | kP KEYWORD2
5 | kD KEYWORD2
6 | kI KEYWORD2
7 | imax KEYWORD2
8 | load_gains KEYWORD2
9 | save_gains KEYWORD2
10 |
--------------------------------------------------------------------------------
/libraries/AC_WPNav/keywords.txt:
--------------------------------------------------------------------------------
1 | Compass KEYWORD1
2 | AP_Compass KEYWORD1
3 | APM_Compass KEYWORD1
4 | init KEYWORD2
5 | read KEYWORD2
6 | calculate KEYWORD2
7 | set_orientation KEYWORD2
8 | set_offsets KEYWORD2
9 | set_declination KEYWORD2
10 | heading KEYWORD2
11 | heading_x KEYWORD2
12 | heading_y KEYWORD2
13 | mag_x KEYWORD2
14 | mag_y KEYWORD2
15 | mag_z KEYWORD2
16 | last_update KEYWORD2
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/libraries/APM_Control/APM_Control.h:
--------------------------------------------------------------------------------
1 | #include "AP_RollController.h"
2 | #include "AP_PitchController.h"
3 | #include "AP_YawController.h"
4 | #include "AP_SteerController.h"
5 |
--------------------------------------------------------------------------------
/libraries/APM_OBC/Failsafe_Board/Makefile:
--------------------------------------------------------------------------------
1 | #
2 | # Trivial makefile for building APM
3 | #
4 | BOARD=uno
5 | include ../../../libraries/../mk/apm.mk
6 |
7 |
--------------------------------------------------------------------------------
/libraries/APM_OBC/Failsafe_Board/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/APM_OBC/Failsafe_Board/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp
--------------------------------------------------------------------------------
/libraries/AP_ADC/examples/AP_ADC_test/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega2560
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/AP_ADC/examples/AP_ADC_test/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_ADC
2 | LIBRARIES += AP_Common
3 | LIBRARIES += AP_Math
4 | LIBRARIES += AP_Param
5 | LIBRARIES += StorageManager
6 |
--------------------------------------------------------------------------------
/libraries/AP_ADC/examples/AP_ADC_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | if bld.env.BOARD in ['sitl']:
6 | return
7 |
8 | bld.ap_example(
9 | use='ap',
10 | )
11 |
--------------------------------------------------------------------------------
/libraries/AP_ADC/keywords.txt:
--------------------------------------------------------------------------------
1 | APM_ADC KEYWORD1
2 | Init KEYWORD2
3 | Ch KEYWORD2
4 |
--------------------------------------------------------------------------------
/libraries/AP_AHRS/AP_AHRS_DCM.cpp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_AHRS/AP_AHRS_DCM.cpp
--------------------------------------------------------------------------------
/libraries/AP_AHRS/examples/AHRS_Test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_AHRS/examples/AHRS_Test/norelax.inoflag:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_AHRS/examples/AHRS_Test/norelax.inoflag
--------------------------------------------------------------------------------
/libraries/AP_AHRS/examples/AHRS_Test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Airspeed/examples/Airspeed/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Airspeed/examples/Airspeed/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Baro/AP_Baro_HIL.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | /*
3 | dummy backend for HIL (and SITL). This doesn't actually need to do
4 | any work, as setHIL() is in the frontend
5 | */
6 | #pragma once
7 |
8 | #include "AP_Baro_Backend.h"
9 |
10 | class AP_Baro_HIL : public AP_Baro_Backend
11 | {
12 | public:
13 | AP_Baro_HIL(AP_Baro &baro);
14 | void update(void);
15 |
16 | private:
17 | uint8_t _instance;
18 | };
19 |
--------------------------------------------------------------------------------
/libraries/AP_Baro/AP_Baro_PX4.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include "AP_Baro_Backend.h"
5 |
6 | class AP_Baro_PX4 : public AP_Baro_Backend
7 | {
8 | public:
9 | AP_Baro_PX4(AP_Baro &);
10 | void update();
11 |
12 | private:
13 | uint8_t _num_instances;
14 |
15 | struct px4_instance {
16 | uint8_t instance;
17 | int fd;
18 | float pressure_sum;
19 | float temperature_sum;
20 | uint32_t sum_count;
21 | uint64_t last_timestamp;
22 | } instances[BARO_MAX_INSTANCES];
23 | };
24 |
--------------------------------------------------------------------------------
/libraries/AP_Baro/examples/BARO_generic/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega2560
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/AP_Baro/examples/BARO_generic/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Common/examples/AP_Common/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Common/examples/AP_Common/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += StorageManager
5 | LIBRARIES += AP_ADC
6 |
--------------------------------------------------------------------------------
/libraries/AP_Common/examples/AP_Common/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Common/keywords.txt:
--------------------------------------------------------------------------------
1 | Menu KEYWORD1
2 | run KEYWORD2
3 | Location KEYWORD2
4 |
5 |
--------------------------------------------------------------------------------
/libraries/AP_Common/missing/ap_version.h:
--------------------------------------------------------------------------------
1 | /* Placeholder header for make build system */
2 |
--------------------------------------------------------------------------------
/libraries/AP_Common/missing/cstddef:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include_next
4 |
5 | #if defined(HAVE_STD_NULLPTR_T) && !HAVE_STD_NULLPTR_T
6 |
7 | namespace std {
8 | typedef decltype(nullptr) nullptr_t;
9 | }
10 |
11 | #endif
12 |
--------------------------------------------------------------------------------
/libraries/AP_Common/missing/type_traits:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #if !defined(HAVE_TYPE_TRAITS_H) || HAVE_TYPE_TRAITS_H
4 | #include_next
5 | #endif
6 |
7 | #if defined(HAVE_STD_REMOVE_REFERENCE) && !HAVE_STD_REMOVE_REFERENCE
8 |
9 | namespace std {
10 | template struct remove_reference { typedef T type; };
11 | template struct remove_reference { typedef T type; };
12 | template struct remove_reference { typedef T type; };
13 | }
14 |
15 | #endif
16 |
--------------------------------------------------------------------------------
/libraries/AP_Common/missing/utility:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include_next
4 |
5 | #if defined(HAVE_STD_MOVE) && !HAVE_STD_MOVE
6 | #include
7 |
8 | namespace std {
9 | template
10 | typename std::remove_reference::type&& move(T&& t) noexcept
11 | {
12 | return static_cast::type&&>(t);
13 | }
14 | }
15 |
16 | #endif
17 |
--------------------------------------------------------------------------------
/libraries/AP_Compass/AP_Compass_HIL.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include "AP_Compass.h"
5 |
6 | #define HIL_NUM_COMPASSES 2
7 |
8 | class AP_Compass_HIL : public AP_Compass_Backend
9 | {
10 | public:
11 | AP_Compass_HIL(Compass &compass);
12 | void read(void);
13 | bool init(void);
14 |
15 | // detect the sensor
16 | static AP_Compass_Backend *detect(Compass &compass);
17 |
18 | private:
19 | uint8_t _compass_instance[HIL_NUM_COMPASSES];
20 | };
21 |
--------------------------------------------------------------------------------
/libraries/AP_Compass/examples/AP_Compass_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Compass/examples/AP_Compass_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Compass/keywords.txt:
--------------------------------------------------------------------------------
1 | Compass KEYWORD1
2 | AP_Compass KEYWORD1
3 | APM_Compass KEYWORD1
4 | init KEYWORD2
5 | read KEYWORD2
6 | calculate KEYWORD2
7 | set_orientation KEYWORD2
8 | set_offsets KEYWORD2
9 | set_declination KEYWORD2
10 | heading KEYWORD2
11 | heading_x KEYWORD2
12 | heading_y KEYWORD2
13 | mag_x KEYWORD2
14 | mag_y KEYWORD2
15 | mag_z KEYWORD2
16 | last_update KEYWORD2
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/libraries/AP_Declination/AP_Declination.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include
5 |
6 | /*
7 | * Adam M Rivera
8 | * With direction from: Andrew Tridgell, Jason Short, Justin Beech
9 | *
10 | * Adapted from: http://www.societyofrobots.com/robotforum/index.php?topic=11855.0
11 | * Scott Ferguson
12 | * scottfromscott@gmail.com
13 | *
14 | */
15 | class AP_Declination
16 | {
17 | public:
18 | static float get_declination(float lat, float lon);
19 | private:
20 | static int16_t get_lookup_value(uint8_t x, uint8_t y);
21 | };
22 |
--------------------------------------------------------------------------------
/libraries/AP_Declination/examples/AP_Declination_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Declination/examples/AP_Declination_test/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Buffer
2 | LIBRARIES += AP_Common
3 | LIBRARIES += AP_Declination
4 | LIBRARIES += AP_Math
5 | LIBRARIES += AP_Param
6 | LIBRARIES += Filter
7 | LIBRARIES += StorageManager
8 | LIBRARIES += AP_ADC
9 |
--------------------------------------------------------------------------------
/libraries/AP_Declination/examples/AP_Declination_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_GPS/examples/GPS_AUTO_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_GPS/examples/GPS_AUTO_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_GPS/tests/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_find_tests(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/AP_HAL_Macros.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | /*
4 | macros to allow code to build on multiple platforms more easily
5 | */
6 |
7 | #ifdef __GNUC__
8 | #define WARN_IF_UNUSED __attribute__ ((warn_unused_result))
9 | #else
10 | #define WARN_IF_UNUSED
11 | #endif
12 |
13 | // use this to avoid issues between C++11 with NuttX and C++10 on
14 | // other platforms.
15 | #if !(defined(__GXX_EXPERIMENTAL_CXX0X__) || __cplusplus >= 201103L)
16 | # define constexpr const
17 | #endif
18 |
19 | #define NORETURN __attribute__ ((noreturn))
20 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/HAL.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #include "HAL.h"
4 |
5 | namespace AP_HAL {
6 |
7 | HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void))
8 | : _setup(setup_fun)
9 | , _loop(loop_fun)
10 | {
11 | assert(setup_fun);
12 | assert(loop_fun);
13 | }
14 |
15 | }
16 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Namespace.h"
4 |
5 | #define HAL_SEMAPHORE_BLOCK_FOREVER ((uint32_t) 0xFFFFFFFF)
6 |
7 | class AP_HAL::Semaphore {
8 | public:
9 | virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
10 | virtual bool take_nonblocking() WARN_IF_UNUSED = 0;
11 | virtual bool give() = 0;
12 | };
13 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/Storage.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include "AP_HAL_Namespace.h"
5 |
6 | class AP_HAL::Storage {
7 | public:
8 | virtual void init() = 0;
9 | virtual void read_block(void *dst, uint16_t src, size_t n) = 0;
10 | virtual void write_block(uint16_t dst, const void* src, size_t n) = 0;
11 | };
12 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/AnalogIn/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/AnalogIn/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += StorageManager
5 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/AnalogIn/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_HAL/examples/AnalogIn/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/AnalogIn/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/Printf/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/Printf/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCInput/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCInput/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCInputToRCOutput/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCInputToRCOutput/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCOutput/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCOutput/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCOutput2/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/RCOutput2/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/Storage/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/Storage/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/UART_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/examples/UART_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/system.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include
6 |
7 | #include "AP_HAL_Macros.h"
8 |
9 | namespace AP_HAL {
10 |
11 | void init();
12 |
13 | void panic(const char *errormsg, ...) FMT_PRINTF(1, 2) NORETURN;
14 |
15 | uint32_t micros();
16 | uint32_t millis();
17 | uint64_t micros64();
18 | uint64_t millis64();
19 |
20 | } // namespace AP_HAL
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/utility/dsm.h:
--------------------------------------------------------------------------------
1 | /*
2 | declaration of dsm_decode from dsm.cpp
3 | */
4 | bool dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16],
5 | uint16_t *values,
6 | uint16_t *num_values,
7 | uint16_t max_values);
8 |
9 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/utility/print_vprintf.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include
6 |
7 | void print_vprintf(AP_HAL::Print *s, const char *fmt, va_list ap);
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL/utility/tests/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_find_tests(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_AVR/README.md:
--------------------------------------------------------------------------------
1 | AVR is only supported on its separate [branch](https://github.com/ArduPilot/ardupilot/tree/master-AVR)
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/AP_HAL_Empty_Namespace.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | namespace Empty {
4 | class AnalogIn;
5 | class AnalogSource;
6 | class DigitalSource;
7 | class GPIO;
8 | class I2CDevice;
9 | class I2CDeviceManager;
10 | class I2CDriver;
11 | class OpticalFlow;
12 | class PrivateMember;
13 | class RCInput;
14 | class RCOutput;
15 | class Scheduler;
16 | class Semaphore;
17 | class SPIDevice;
18 | class SPIDeviceDriver;
19 | class SPIDeviceManager;
20 | class Storage;
21 | class UARTDriver;
22 | class Util;
23 | }
24 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/AP_HAL_Empty_Private.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | /* Umbrella header for all private headers of the AP_HAL_Empty module.
4 | * Only import this header from inside AP_HAL_Empty
5 | */
6 |
7 | #include "AnalogIn.h"
8 | #include "GPIO.h"
9 | #include "I2CDevice.h"
10 | #include "I2CDriver.h"
11 | #include "OpticalFlow.h"
12 | #include "PrivateMember.h"
13 | #include "RCInput.h"
14 | #include "RCOutput.h"
15 | #include "Scheduler.h"
16 | #include "Semaphores.h"
17 | #include "SPIDriver.h"
18 | #include "Storage.h"
19 | #include "UARTDriver.h"
20 | #include "Util.h"
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/HAL_Empty_Class.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include "AP_HAL_Empty_Namespace.h"
6 | #include "PrivateMember.h"
7 |
8 | class HAL_Empty : public AP_HAL::HAL {
9 | public:
10 | HAL_Empty();
11 | void run(int argc, char* const* argv, Callbacks* callbacks) const override;
12 | private:
13 | Empty::PrivateMember *_member;
14 | };
15 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/PrivateMember.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include "PrivateMember.h"
3 |
4 | using namespace Empty;
5 |
6 | PrivateMember::PrivateMember(uint16_t foo) :
7 | _foo(foo)
8 | {}
9 |
10 | void PrivateMember::init() {}
11 |
12 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/PrivateMember.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | /* Just a stub as an example of how to implement a private member of an
4 | * AP_HAL module */
5 |
6 | #include "AP_HAL_Empty.h"
7 |
8 | class Empty::PrivateMember {
9 | public:
10 | PrivateMember(uint16_t foo);
11 | void init();
12 | private:
13 | uint16_t _foo;
14 | };
15 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/RCInput.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Empty.h"
4 |
5 | class Empty::RCInput : public AP_HAL::RCInput {
6 | public:
7 | RCInput();
8 | void init();
9 | bool new_input();
10 | uint8_t num_channels();
11 | uint16_t read(uint8_t ch);
12 | uint8_t read(uint16_t* periods, uint8_t len);
13 |
14 | bool set_overrides(int16_t *overrides, uint8_t len);
15 | bool set_override(uint8_t channel, int16_t override);
16 | void clear_overrides();
17 | };
18 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/RCOutput.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include "RCOutput.h"
3 |
4 | using namespace Empty;
5 |
6 | void RCOutput::init() {}
7 |
8 | void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {}
9 |
10 | uint16_t RCOutput::get_freq(uint8_t ch) {
11 | return 50;
12 | }
13 |
14 | void RCOutput::enable_ch(uint8_t ch)
15 | {}
16 |
17 | void RCOutput::disable_ch(uint8_t ch)
18 | {}
19 |
20 | void RCOutput::write(uint8_t ch, uint16_t period_us)
21 | {}
22 |
23 | uint16_t RCOutput::read(uint8_t ch) {
24 | return 900;
25 | }
26 |
27 | void RCOutput::read(uint16_t* period_us, uint8_t len)
28 | {}
29 |
30 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/RCOutput.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Empty.h"
4 |
5 | class Empty::RCOutput : public AP_HAL::RCOutput {
6 | void init();
7 | void set_freq(uint32_t chmask, uint16_t freq_hz);
8 | uint16_t get_freq(uint8_t ch);
9 | void enable_ch(uint8_t ch);
10 | void disable_ch(uint8_t ch);
11 | void write(uint8_t ch, uint16_t period_us);
12 | uint16_t read(uint8_t ch);
13 | void read(uint16_t* period_us, uint8_t len);
14 | };
15 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/Semaphores.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include "Semaphores.h"
3 |
4 | using namespace Empty;
5 |
6 | bool Semaphore::give() {
7 | if (_taken) {
8 | _taken = false;
9 | return true;
10 | } else {
11 | return false;
12 | }
13 | }
14 |
15 | bool Semaphore::take(uint32_t timeout_ms) {
16 | return take_nonblocking();
17 | }
18 |
19 | bool Semaphore::take_nonblocking() {
20 | /* No syncronisation primitives to garuntee this is correct */
21 | if (!_taken) {
22 | _taken = true;
23 | return true;
24 | } else {
25 | return false;
26 | }
27 | }
28 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Empty.h"
4 |
5 | class Empty::Semaphore : public AP_HAL::Semaphore {
6 | public:
7 | Semaphore() : _taken(false) {}
8 | bool give();
9 | bool take(uint32_t timeout_ms);
10 | bool take_nonblocking();
11 | private:
12 | bool _taken;
13 | };
14 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/Storage.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include
3 | #include "Storage.h"
4 |
5 | using namespace Empty;
6 |
7 | Storage::Storage()
8 | {}
9 |
10 | void Storage::init()
11 | {}
12 |
13 | void Storage::read_block(void* dst, uint16_t src, size_t n) {
14 | memset(dst, 0, n);
15 | }
16 |
17 | void Storage::write_block(uint16_t loc, const void* src, size_t n)
18 | {}
19 |
20 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/Storage.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Empty.h"
4 |
5 | class Empty::Storage : public AP_HAL::Storage {
6 | public:
7 | Storage();
8 | void init();
9 | void read_block(void *dst, uint16_t src, size_t n);
10 | void write_block(uint16_t dst, const void* src, size_t n);
11 | };
12 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Empty/Util.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include "AP_HAL_Empty_Namespace.h"
5 |
6 | class Empty::Util : public AP_HAL::Util {
7 | public:
8 | bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; }
9 | };
10 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_FLYMAPLE/README.md:
--------------------------------------------------------------------------------
1 | FLYMAPLE is only supported on its separate [branch](https://github.com/ArduPilot/ardupilot/tree/master-AVR)
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/GPIO.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #include "GPIO.h"
4 |
5 | using namespace Linux;
6 |
7 | static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
8 |
9 | DigitalSource::DigitalSource(uint8_t v) :
10 | _v(v)
11 | {
12 |
13 | }
14 |
15 | void DigitalSource::mode(uint8_t output)
16 | {
17 | hal.gpio->pinMode(_v, output);
18 | }
19 |
20 | uint8_t DigitalSource::read()
21 | {
22 | return hal.gpio->read(_v);
23 | }
24 |
25 | void DigitalSource::write(uint8_t value)
26 | {
27 | return hal.gpio->write(_v,value);
28 | }
29 |
30 | void DigitalSource::toggle()
31 | {
32 | write(!read());
33 | }
34 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/GPIO_Bebop.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #include "GPIO_Bebop.h"
4 |
5 | #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
6 |
7 | const unsigned Linux::GPIO_Sysfs::pin_table[] = {
8 | [BEBOP_GPIO_CAMV_NRST] = 129,
9 | [LINUX_GPIO_ULTRASOUND_VOLTAGE] = 200,
10 | };
11 |
12 | const uint8_t Linux::GPIO_Sysfs::n_pins = _BEBOP_GPIO_MAX;
13 |
14 | static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _BEBOP_GPIO_MAX,
15 | "GPIO pin_table must have the same size of entries in enum gpio_bebop");
16 |
17 | #endif
18 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/GPIO_Bebop.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "GPIO_Sysfs.h"
4 |
5 | enum gpio_bebop {
6 | BEBOP_GPIO_CAMV_NRST,
7 | LINUX_GPIO_ULTRASOUND_VOLTAGE,
8 | _BEBOP_GPIO_MAX,
9 | };
10 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/HAL_Linux_Class.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include "AP_HAL_Linux_Namespace.h"
6 |
7 | class HAL_Linux : public AP_HAL::HAL {
8 | public:
9 | HAL_Linux();
10 | void run(int argc, char* const* argv, Callbacks* callbacks) const override;
11 | };
12 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/RCInput_Navio2.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "RCInput.h"
4 |
5 | class Linux::RCInput_Navio2 : public Linux::RCInput
6 | {
7 | public:
8 | void init() override;
9 | void _timer_tick(void) override;
10 | RCInput_Navio2();
11 | ~RCInput_Navio2();
12 |
13 | private:
14 | int open_channel(int ch);
15 |
16 | uint64_t _last_timestamp = 0l;
17 | static const size_t CHANNEL_COUNT = 16;
18 | int channels[CHANNEL_COUNT];
19 | uint16_t periods[ARRAY_SIZE(channels)] = {0};
20 | };
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/RCInput_Raspilot.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Linux.h"
4 | #include "RCInput.h"
5 |
6 | class Linux::RCInput_Raspilot : public Linux::RCInput
7 | {
8 | public:
9 | void init();
10 |
11 | private:
12 | uint32_t _last_timer;
13 |
14 | AP_HAL::SPIDeviceDriver *_spi;
15 | AP_HAL::Semaphore *_spi_sem;
16 |
17 | void _poll_data(void);
18 | };
19 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/RCInput_UART.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include "AP_HAL_Linux.h"
6 | #include "RCInput.h"
7 |
8 | #define CHANNELS 8
9 |
10 | class Linux::RCInput_UART : public Linux::RCInput
11 | {
12 | public:
13 | RCInput_UART(const char *path);
14 | ~RCInput_UART();
15 |
16 | void init() override;
17 | void _timer_tick(void) override;
18 |
19 | private:
20 | int _fd;
21 | uint8_t *_pdata;
22 | ssize_t _remain;
23 | struct PACKED {
24 | uint16_t magic;
25 | uint16_t values[CHANNELS];
26 | } _data;
27 | };
28 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/RCInput_UDP.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "RCInput.h"
4 | #include
5 | #include "RCInput_UDP_Protocol.h"
6 |
7 | #define RCINPUT_UDP_DEF_PORT 777
8 |
9 | class Linux::RCInput_UDP : public Linux::RCInput
10 | {
11 | public:
12 | RCInput_UDP();
13 | void init();
14 | void _timer_tick(void);
15 | private:
16 | SocketAPM _socket{true};
17 | uint16_t _port;
18 | struct rc_udp_packet _buf;
19 | uint64_t _last_buf_ts;
20 | uint16_t _last_buf_seq;
21 | };
22 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/RCInput_UDP_Protocol.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #define RCINPUT_UDP_NUM_CHANNELS 8
4 | #define RCINPUT_UDP_VERSION 2
5 |
6 | struct __attribute__((packed)) rc_udp_packet {
7 | uint32_t version;
8 | uint64_t timestamp_us;
9 | uint16_t sequence;
10 | uint16_t pwms[RCINPUT_UDP_NUM_CHANNELS];
11 | };
12 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #include
6 |
7 | #include "AP_HAL_Linux.h"
8 |
9 | class Linux::Semaphore : public AP_HAL::Semaphore {
10 | public:
11 | Semaphore() {
12 | pthread_mutex_init(&_lock, NULL);
13 | }
14 | bool give();
15 | bool take(uint32_t timeout_ms);
16 | bool take_nonblocking();
17 | private:
18 | pthread_mutex_t _lock;
19 | };
20 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/SerialDevice.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 |
6 | class SerialDevice {
7 | public:
8 | virtual ~SerialDevice() {}
9 |
10 | virtual bool open() = 0;
11 | virtual bool close() = 0;
12 | virtual ssize_t write(const uint8_t *buf, uint16_t n) = 0;
13 | virtual ssize_t read(uint8_t *buf, uint16_t n) = 0;
14 | virtual void set_blocking(bool blocking) = 0;
15 | virtual void set_speed(uint32_t speed) = 0;
16 | };
17 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/ToneAlarm_Raspilot.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_Linux.h"
4 |
5 | #include "ToneAlarm.h"
6 |
7 | class Linux::ToneAlarm_Raspilot : public Linux::ToneAlarm {
8 | public:
9 | ToneAlarm_Raspilot();
10 | bool init() override;
11 | void stop() override;
12 | bool play() override;
13 |
14 | private:
15 | void _set_pwm0_period(uint32_t time_us);
16 | void _set_pwm0_duty(uint8_t percent);
17 |
18 | volatile uint32_t *_pwm;
19 | volatile uint32_t *_clk;
20 | };
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/Util_RPI.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "Util.h"
4 |
5 | class Linux::UtilRPI : public Linux::Util {
6 | public:
7 | UtilRPI();
8 |
9 | static UtilRPI *from(AP_HAL::Util *util) {
10 | return static_cast(util);
11 | }
12 |
13 | /* return the Raspberry Pi version */
14 | int get_rpi_version() const;
15 |
16 | protected:
17 | // Called in the constructor once
18 | int _check_rpi_version();
19 |
20 | private:
21 | int _rpi_version = 0;
22 | };
23 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/benchmarks/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_find_benchmarks(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/BusTest/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/BusTest/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += StorageManager
5 | LIBRARIES += AP_ADC
6 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/BusTest/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_HAL_Linux/examples/BusTest/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/BusTest/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/GPIOTest/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/examples/GPIOTest/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += StorageManager
2 | LIBRARIES += AP_Menu
3 | LIBRARIES += AP_ADC
4 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/qflight/qflight_dsp.idl:
--------------------------------------------------------------------------------
1 | #include "AEEStdDef.idl"
2 |
3 | interface qflight {
4 | // sensor calls
5 | long get_imu_data(rout sequence outdata);
6 | long get_mag_data(rout sequence outdata);
7 | long get_baro_data(rout sequence outdata);
8 |
9 | // UART control
10 | long UART_open(in string device, rout int32 fd);
11 | long UART_set_baudrate(in int32 fd, in uint32 baudrate);
12 | long UART_read(in int32 fd, rout sequence buf, rout int32 nread);
13 | long UART_write(in int32 fd, in sequence buf, rout int32 nwritten);
14 | long UART_close(in int32 fd);
15 | };
16 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/qflight/qflight_util.h:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #define QFLIGHT_RPC_ALLOCATE(type) (type *)rpcmem_alloc_def(sizeof(type))
4 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_Linux/sbus.h:
--------------------------------------------------------------------------------
1 | /*
2 | declarations for sbus.h
3 | */
4 | bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
5 | bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values);
6 |
7 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/AP_HAL_PX4.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
6 | #include "HAL_PX4_Class.h"
7 |
8 | #endif // CONFIG_HAL_BOARD
9 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/AP_HAL_PX4_Namespace.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | namespace PX4 {
4 | class PX4Scheduler;
5 | class PX4UARTDriver;
6 | class PX4Storage;
7 | class PX4RCInput;
8 | class PX4RCOutput;
9 | class PX4AnalogIn;
10 | class PX4AnalogSource;
11 | class PX4Util;
12 | class PX4GPIO;
13 | class PX4DigitalSource;
14 | class NSHShellStream;
15 | class PX4I2CDriver;
16 | class PX4_I2C;
17 | class Semaphore;
18 | }
19 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/HAL_PX4_Class.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
6 |
7 | #include "AP_HAL_PX4.h"
8 | #include "AP_HAL_PX4_Namespace.h"
9 | #include
10 | #include
11 |
12 | class HAL_PX4 : public AP_HAL::HAL {
13 | public:
14 | HAL_PX4();
15 | void run(int argc, char* const argv[], Callbacks* callbacks) const override;
16 | };
17 |
18 | void hal_px4_set_priority(uint8_t priority);
19 |
20 | #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
6 | #include "AP_HAL_PX4.h"
7 | #include
8 |
9 | class PX4::Semaphore : public AP_HAL::Semaphore {
10 | public:
11 | Semaphore() {
12 | pthread_mutex_init(&_lock, NULL);
13 | }
14 | bool give();
15 | bool take(uint32_t timeout_ms);
16 | bool take_nonblocking();
17 | private:
18 | pthread_mutex_t _lock;
19 | };
20 | #endif // CONFIG_HAL_BOARD
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/examples/simple/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/examples/simple/simple.cpp:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | /*
4 | simple hello world sketch
5 | Andrew Tridgell September 2011
6 | */
7 |
8 | #include
9 |
10 | const AP_HAL::HAL& hal = AP_HAL::get_HAL();
11 |
12 | void setup() {
13 | hal.console->println("hello world");
14 | }
15 |
16 | void loop()
17 | {
18 | hal.scheduler->delay(1000);
19 | hal.console->println("*");
20 | }
21 |
22 | AP_HAL_MAIN();
23 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_PX4/examples/simple/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_QURT/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_QURT
6 | #include "AP_HAL_QURT.h"
7 | #include
8 |
9 | class QURT::Semaphore : public AP_HAL::Semaphore {
10 | public:
11 | Semaphore() {
12 | pthread_mutex_init(&_lock, NULL);
13 | }
14 | bool give();
15 | bool take(uint32_t timeout_ms);
16 | bool take_nonblocking();
17 | private:
18 | pthread_mutex_t _lock;
19 | };
20 | #endif // CONFIG_HAL_BOARD
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_QURT/Util.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #if CONFIG_HAL_BOARD == HAL_BOARD_QURT
3 | #include "Semaphores.h"
4 | #include
5 |
6 | extern const AP_HAL::HAL& hal;
7 |
8 | #include "Util.h"
9 |
10 | using namespace QURT;
11 |
12 | /*
13 | always report 256k of free memory. I don't know how to query
14 | available memory on QURT
15 | */
16 | uint32_t Util::available_memory(void)
17 | {
18 | return 256*1024;
19 | }
20 |
21 | // create a new semaphore
22 | Semaphore *Util::new_semaphore(void)
23 | {
24 | return new Semaphore;
25 | }
26 |
27 | #endif // CONFIG_HAL_BOARD == HAL_BOARD_QURT
28 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_QURT/qurt_dsp.idl:
--------------------------------------------------------------------------------
1 | #include "AEEStdDef.idl"
2 |
3 | interface ardupilot {
4 | // start main thread
5 | uint32 start(in sequence cmdline);
6 |
7 | // a heartbeat for debugging
8 | uint32 heartbeat();
9 |
10 | // get eeprom updates
11 | uint32 set_storage(in sequence eeprom);
12 | uint32 get_storage(rout sequence eeprom);
13 |
14 | // handle socket data
15 | uint32 socket_check(rout sequence buf, rout uint32 nbytes);
16 | uint32 socket_input(in sequence buf, rout uint32 nbytes);
17 | };
18 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/AP_HAL_SITL.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 |
7 | #include "HAL_SITL_Class.h"
8 |
9 | #endif // CONFIG_HAL_BOARD
10 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | namespace HALSITL {
4 | class UARTDriver;
5 | class Scheduler;
6 | class SITL_State;
7 | class EEPROMStorage;
8 | class AnalogIn;
9 | class RCInput;
10 | class RCOutput;
11 | class ADCSource;
12 | class RCInput;
13 | class Util;
14 | class Semaphore;
15 | }
16 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/AP_HAL_SITL_Private.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include "AP_HAL_SITL_Namespace.h"
4 | #include "Scheduler.h"
5 | #include "Storage.h"
6 | #include "UARTDriver.h"
7 | #include "SITL_State.h"
8 | #include "Semaphores.h"
9 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/HAL_SITL_Class.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 |
7 | #include "AP_HAL_SITL.h"
8 | #include "AP_HAL_SITL_Namespace.h"
9 | #include "SITL_State.h"
10 |
11 | class HAL_SITL : public AP_HAL::HAL {
12 | public:
13 | HAL_SITL();
14 | void run(int argc, char * const argv[], Callbacks* callbacks) const override;
15 |
16 | private:
17 | HALSITL::SITL_State *_sitl_state;
18 | };
19 |
20 | #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
21 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/Semaphores.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 | #include "AP_HAL_SITL.h"
7 | #include
8 |
9 | class HALSITL::Semaphore : public AP_HAL::Semaphore {
10 | public:
11 | Semaphore() {
12 | pthread_mutex_init(&_lock, NULL);
13 | }
14 | bool give();
15 | bool take(uint32_t timeout_ms);
16 | bool take_nonblocking();
17 | private:
18 | pthread_mutex_t _lock;
19 | };
20 | #endif // CONFIG_HAL_BOARD
21 |
22 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_SITL/Storage.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include "AP_HAL_SITL_Namespace.h"
5 |
6 | class HALSITL::EEPROMStorage : public AP_HAL::Storage {
7 | public:
8 | EEPROMStorage() {
9 | _eeprom_fd = -1;
10 | }
11 | void init() {}
12 | void read_block(void *dst, uint16_t src, size_t n);
13 | void write_block(uint16_t dst, const void* src, size_t n);
14 |
15 | private:
16 | int _eeprom_fd;
17 | void _eeprom_open(void);
18 | };
19 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_VRBRAIN/AP_HAL_VRBRAIN.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
6 | #include "HAL_VRBRAIN_Class.h"
7 |
8 | #endif // CONFIG_HAL_BOARD
9 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_VRBRAIN/AP_HAL_VRBRAIN_Namespace.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | namespace VRBRAIN {
4 | class VRBRAINScheduler;
5 | class VRBRAINUARTDriver;
6 | class VRBRAINStorage;
7 | class VRBRAINRCInput;
8 | class VRBRAINRCOutput;
9 | class VRBRAINAnalogIn;
10 | class VRBRAINAnalogSource;
11 | class VRBRAINUtil;
12 | class VRBRAINGPIO;
13 | class VRBRAINDigitalSource;
14 | }
15 |
--------------------------------------------------------------------------------
/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
6 |
7 | #include "AP_HAL_VRBRAIN.h"
8 | #include "AP_HAL_VRBRAIN_Namespace.h"
9 | #include
10 | #include
11 |
12 | class HAL_VRBRAIN : public AP_HAL::HAL {
13 | public:
14 | HAL_VRBRAIN();
15 | void run(int argc, char* const argv[], Callbacks* callbacks) const override;
16 | };
17 |
18 | #endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
19 |
--------------------------------------------------------------------------------
/libraries/AP_IRLock/AP_IRLock.h:
--------------------------------------------------------------------------------
1 | /*
2 | * AP_IRLock.h
3 | *
4 | * Created on: Nov 10, 2014
5 | * Author: MLandes
6 | */
7 |
8 | // @file AP_IRLock.h
9 | // @brief Catch-all headerthat defines all supported irlock classes.
10 |
11 | #include "IRLock.h"
12 | #include "AP_IRLock_PX4.h"
13 |
--------------------------------------------------------------------------------
/libraries/AP_IRLock/AP_IRLock_PX4.h:
--------------------------------------------------------------------------------
1 | /*
2 | * AP_IRLock_PX4.h
3 | *
4 | * Created on: Nov 10, 2014
5 | * Author: MLandes
6 | */
7 | #pragma once
8 |
9 | #include "IRLock.h"
10 |
11 | class AP_IRLock_PX4 : public IRLock
12 | {
13 | public:
14 | AP_IRLock_PX4();
15 |
16 | // init - initialize sensor library
17 | virtual void init();
18 |
19 | // retrieve latest sensor data - returns true if new data is available
20 | virtual bool update();
21 |
22 | private:
23 | int _fd;
24 | uint64_t _last_timestamp;
25 | };
26 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include "AP_InertialSensor.h"
5 | #include "AP_InertialSensor_Backend.h"
6 |
7 | class AP_InertialSensor_HIL : public AP_InertialSensor_Backend
8 | {
9 | public:
10 | AP_InertialSensor_HIL(AP_InertialSensor &imu);
11 |
12 | /* update accel and gyro state */
13 | bool update();
14 |
15 | // detect the sensor
16 | static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
17 |
18 | private:
19 | bool _init_sensor(void);
20 | };
21 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | /* Pure virtual interface class */
6 | class AP_InertialSensor_UserInteract {
7 | public:
8 | virtual bool blocking_read() = 0;
9 | virtual void printf(const char *, ...) FMT_PRINTF(2, 3) = 0;
10 | };
11 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_Stream.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 |
6 | #include "AP_InertialSensor_UserInteract.h"
7 |
8 | /**
9 | * AP_InertialSensor_UserInteract, implemented in terms of a BetterStream.
10 | */
11 | class AP_InertialSensor_UserInteractStream : public AP_InertialSensor_UserInteract {
12 | public:
13 | AP_InertialSensor_UserInteractStream(AP_HAL::BetterStream *s) :
14 | _s(s) {}
15 |
16 | bool blocking_read();
17 | void printf(const char*, ...) FMT_PRINTF(2, 3);
18 | private:
19 | AP_HAL::BetterStream *_s;
20 | };
21 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/examples/INS_generic/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/examples/INS_generic/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/examples/VibTest/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_InertialSensor/examples/VibTest/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | # TODO: Test code doesn't build. Fix or delete the test.
6 | return
7 | bld.ap_example(
8 | use='ap',
9 | )
10 |
--------------------------------------------------------------------------------
/libraries/AP_L1_Control/keywords.txt:
--------------------------------------------------------------------------------
1 | AP_L1_Control KEYWORD1
--------------------------------------------------------------------------------
/libraries/AP_Math/benchmarks/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_find_benchmarks(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/eulers/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/eulers/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/location/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/location/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/matrix_alg/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/matrix_alg/nocore.inoflag:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_Math/examples/matrix_alg/nocore.inoflag
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/polygon/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/polygon/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/rotations/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Math/examples/rotations/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/tests/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_find_tests(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Math/tools/geodesic_grid/README.md:
--------------------------------------------------------------------------------
1 | # Geodesic Grid Tool #
2 |
3 | This folder a toolset for helping understanding the concepts used by
4 | [`AP_GeodesicGrid`](../../AP_GeodesicGrid.cpp) as well as for aiding its
5 | development. The main script is named `geodesic_grid.py`. Use `geodesic_grid.py
6 | --help` to know how to use it.
7 |
--------------------------------------------------------------------------------
/libraries/AP_Math/vector2.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_Math/vector2.h
--------------------------------------------------------------------------------
/libraries/AP_Math/vector3.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_Math/vector3.h
--------------------------------------------------------------------------------
/libraries/AP_Mission/examples/AP_Mission_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Mission/examples/AP_Mission_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Motors/AP_Motors.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include "AP_Motors_Class.h"
5 | #include "AP_MotorsMulticopter.h"
6 | #include "AP_MotorsMatrix.h"
7 | #include "AP_MotorsTri.h"
8 | #include "AP_MotorsQuad.h"
9 | #include "AP_MotorsHexa.h"
10 | #include "AP_MotorsY6.h"
11 | #include "AP_MotorsOcta.h"
12 | #include "AP_MotorsOctaQuad.h"
13 | #include "AP_MotorsHeli_Single.h"
14 | #include "AP_MotorsSingle.h"
15 | #include "AP_MotorsCoax.h"
16 |
--------------------------------------------------------------------------------
/libraries/AP_Motors/examples/AP_Motors_test/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
4 |
--------------------------------------------------------------------------------
/libraries/AP_Motors/examples/AP_Motors_test/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_Motors/examples/AP_Motors_test/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_Motors/examples/AP_Motors_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | # TODO: Test code doesn't build. Fix or delete the test.
6 | return
7 |
8 | bld.ap_example(
9 | use='ap',
10 | )
11 |
--------------------------------------------------------------------------------
/libraries/AP_Mount/examples/trivial_AP_Mount/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Mount/examples/trivial_AP_Mount/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/AttErrVecMathExample/with_initial_alignment.fig:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_NavEKF/Models/AttErrVecMathExample/with_initial_alignment.fig
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/NormQuat.m:
--------------------------------------------------------------------------------
1 | % normalise the quaternion
2 | function quaternion = normQuat(quaternion)
3 |
4 | quatMag = sqrt(quaternion(1)^2 + quaternion(2)^2 + quaternion(3)^2 + quaternion(4)^2);
5 | quaternion(1:4) = quaternion / quatMag;
6 |
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/Quat2Tbn.m:
--------------------------------------------------------------------------------
1 | function Tbn = Quat2Tbn(quat)
2 |
3 | % Convert from quaternions defining the flight vehicles rotation to
4 | % the direction cosine matrix defining the rotation from body to navigation
5 | % coordinates
6 |
7 | q0 = quat(1);
8 | q1 = quat(2);
9 | q2 = quat(3);
10 | q3 = quat(4);
11 |
12 | Tbn = [q0^2 + q1^2 - q2^2 - q3^2, 2*(q1*q2 - q0*q3), 2*(q1*q3 + q0*q2); ...
13 | 2*(q1*q2 + q0*q3), q0^2 - q1^2 + q2^2 - q3^2, 2*(q2*q3 - q0*q1); ...
14 | 2*(q1*q3-q0*q2), 2*(q2*q3 + q0*q1), q0^2 - q1^2 - q2^2 + q3^2];
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/QuatDivide.m:
--------------------------------------------------------------------------------
1 | function q_out = QuatDivide(qin1,qin2)
2 |
3 | q0 = qin1(1);
4 | q1 = qin1(2);
5 | q2 = qin1(3);
6 | q3 = qin1(4);
7 |
8 | r0 = qin2(1);
9 | r1 = qin2(2);
10 | r2 = qin2(3);
11 | r3 = qin2(4);
12 |
13 | q_out(1,1) = (qin2(1)*qin1(1) + qin2(2)*qin1(2) + qin2(3)*qin1(3) + qin2(4)*qin1(4));
14 | q_out(2,1) = (r0*q1 - r1*q0 - r2*q3 + r3*q2);
15 | q_out(3,1) = (r0*q2 + r1*q3 - r2*q0 - r3*q1);
16 | q_out(4,1) = (r0*q3 - r1*q2 + r2*q1 - r3*q0);
17 |
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/QuatMult.m:
--------------------------------------------------------------------------------
1 | function quatOut = QuatMult(quatA,quatB)
2 | % Calculate the following quaternion product quatA * quatB using the
3 | % standard identity
4 |
5 | quatOut = [quatA(1)*quatB(1)-quatA(2:4)'*quatB(2:4); quatA(1)*quatB(2:4) + quatB(1)*quatA(2:4) + cross(quatA(2:4),quatB(2:4))];
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/QuatToEul.m:
--------------------------------------------------------------------------------
1 | % Convert from a quaternion to a 321 Euler rotation sequence in radians
2 |
3 | function Euler = QuatToEul(quat)
4 |
5 | Euler = zeros(3,1);
6 |
7 | Euler(1) = atan2(2*(quat(3)*quat(4)+quat(1)*quat(2)), quat(1)*quat(1) - quat(2)*quat(2) - quat(3)*quat(3) + quat(4)*quat(4));
8 | Euler(2) = -asin(2*(quat(2)*quat(4)-quat(1)*quat(3)));
9 | Euler(3) = atan2(2*(quat(2)*quat(3)+quat(1)*quat(4)), quat(1)*quat(1) + quat(2)*quat(2) - quat(3)*quat(3) - quat(4)*quat(4));
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/Common/RotToQuat.m:
--------------------------------------------------------------------------------
1 | % convert froma rotation vector in radians to a quaternion
2 | function quaternion = RotToQuat(rotVec)
3 |
4 | vecLength = sqrt(rotVec(1)^2 + rotVec(2)^2 + rotVec(3)^2);
5 |
6 | if vecLength < 1e-6
7 | quaternion = [1;0;0;0];
8 | else
9 | quaternion = [cos(0.5*vecLength); rotVec/vecLength*sin(0.5*vecLength)];
10 | end
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcF.c:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcF.c
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcF.cpp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcF.cpp
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.c:
--------------------------------------------------------------------------------
1 | t0 = _symans_32_297;
2 |
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.m:
--------------------------------------------------------------------------------
1 | function Tms = calcTms(gPhi,gPsi,gTheta)
2 | %CALCTMS
3 | % TMS = CALCTMS(GPHI,GPSI,GTHETA)
4 |
5 | % This function was generated by the Symbolic Math Toolbox version 6.1.
6 | % 15-Feb-2015 16:02:09
7 |
8 | t2 = cos(gTheta);
9 | t3 = sin(gPsi);
10 | t4 = cos(gPsi);
11 | t5 = sin(gPhi);
12 | t6 = sin(gTheta);
13 | t7 = cos(gPhi);
14 | Tms = reshape([t2.*t4-t3.*t5.*t6,-t3.*t7,t4.*t6+t2.*t3.*t5,t2.*t3+t4.*t5.*t6,t4.*t7,t3.*t6-t2.*t4.*t5,-t6.*t7,t5,t2.*t7],[3, 3]);
15 |
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/QuaternionMathExample/PlotData.m:
--------------------------------------------------------------------------------
1 | %% plot gyro bias estimates
2 | figure;
3 | plot(statesLog(1,:)*0.001,statesLog(9:11,:)/dt*180/pi);
4 | grid on;
5 | ylabel('Gyro Bias Estimate (deg/sec)');
6 | xlabel('time (sec)');
7 |
8 | %% plot Euler angle estimates
9 | figure;
10 | eulLog(4,:) = eulLog(4,:) + pi;
11 | plot(eulLog(1,:)*0.001,eulLog(2:4,:)*180/pi);
12 | grid on;
13 | ylabel('Euler Angle Estimates (deg)');
14 | xlabel('time (sec)');
15 |
16 | %% plot velocity innovations
17 | figure;
18 | plot(statesLog(1,:)*0.001,statesLog(6:8,:));
19 | grid on;
20 | ylabel('EKF velocity Innovations (m/s)');
21 | xlabel('time (sec)');
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/testData/fltTest.mat:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_NavEKF/Models/testData/fltTest.mat
--------------------------------------------------------------------------------
/libraries/AP_NavEKF/Models/testData/gndTest.mat:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_NavEKF/Models/testData/gndTest.mat
--------------------------------------------------------------------------------
/libraries/AP_Notify/NotifyDevice.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 | #include
5 |
6 | class AP_Notify;
7 |
8 | class NotifyDevice {
9 | public:
10 | virtual ~NotifyDevice() {}
11 | // init - initialised the device
12 | virtual bool init(void) = 0;
13 | // update - updates device according to timed_updated. Should be
14 | // called at 50Hz
15 | virtual void update() = 0;
16 |
17 | // this pointer is used to read the parameters relative to devices
18 | const AP_Notify *pNotify;
19 | };
20 |
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/AP_Notify_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/AP_Notify_test/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Notify
4 | LIBRARIES += AP_Param
5 | LIBRARIES += AP_RangeFinder
6 | LIBRARIES += GCS_MAVLink
7 | LIBRARIES += StorageManager
8 |
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/AP_Notify_test/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_Notify/examples/AP_Notify_test/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/AP_Notify_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/ToshibaLED_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Notify/examples/ToshibaLED_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_OpticalFlow/AP_OpticalFlow.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | /// @file AP_OpticalFlow.h
4 | /// @brief Catch-all header that defines all supported optical flow classes.
5 |
6 | #include "OpticalFlow.h"
7 |
--------------------------------------------------------------------------------
/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h:
--------------------------------------------------------------------------------
1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 | #pragma once
3 |
4 | #include "OpticalFlow.h"
5 |
6 | class AP_OpticalFlow_HIL : public OpticalFlow_backend
7 | {
8 | public:
9 | /// constructor
10 | AP_OpticalFlow_HIL(OpticalFlow &_frontend);
11 |
12 | // init - initialise the sensor
13 | void init();
14 |
15 | // update - read latest values from sensor and fill in x,y and totals.
16 | void update(void);
17 | };
18 |
--------------------------------------------------------------------------------
/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega2560
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/nobuild.txt
--------------------------------------------------------------------------------
/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Parachute/examples/AP_Parachute_test/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Notify
4 | LIBRARIES += AP_Parachute
5 | LIBRARIES += AP_Param
6 | LIBRARIES += AP_Relay
7 | LIBRARIES += RC_Channel
8 | LIBRARIES += StorageManager
9 |
--------------------------------------------------------------------------------
/libraries/AP_Parachute/examples/AP_Parachute_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_RPM/examples/RPM_generic/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_RPM/examples/RPM_generic/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_RangeFinder/AP_RangeFinder.h:
--------------------------------------------------------------------------------
1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2 |
3 | /// @file AP_RangeFinder.h
4 | /// @brief Catch-all header that defines all supported RangeFinder classes.
5 |
6 | #include "RangeFinder.h"
7 |
--------------------------------------------------------------------------------
/libraries/AP_RangeFinder/examples/RFIND_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_RangeFinder/examples/RFIND_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/AP_Scheduler/examples/Scheduler_test/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/AP_Scheduler/examples/Scheduler_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_AllTypes/Makefile:
--------------------------------------------------------------------------------
1 | #BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_AllTypes/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common # for new() overrides
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Mission
4 | LIBRARIES += AP_Param
5 | LIBRARIES += DataFlash
6 | LIBRARIES += GCS_MAVLink
7 | LIBRARIES += StorageManager
8 | LIBRARIES += AP_Scheduler
9 | LIBRARIES += AP_ADC
10 |
11 |
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_AllTypes/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_test/Makefile:
--------------------------------------------------------------------------------
1 | #BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_test/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/DataFlash/examples/DataFlash_test/nobuild.txt
--------------------------------------------------------------------------------
/libraries/DataFlash/examples/DataFlash_test/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/Filter/Filter.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | /* Umbrella header for the Filter library */
4 |
5 | #include "FilterClass.h"
6 | #include "AverageFilter.h"
7 | #include "DerivativeFilter.h"
8 | #include "FilterWithBuffer.h"
9 | #include "LowPassFilter.h"
10 | #include "ModeFilter.h"
11 | #include "Butter.h"
12 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Derivative/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Derivative/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += Filter
5 | LIBRARIES += StorageManager
6 | LIBRARIES += AP_ADC
7 |
8 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Derivative/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Filter/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Filter/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += Filter
5 | LIBRARIES += StorageManager
6 | LIBRARIES += AP_ADC
7 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/Filter/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += Filter
5 | LIBRARIES += StorageManager
6 | LIBRARIES += AP_ADC
7 |
8 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter2p/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter2p/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += Filter
5 | LIBRARIES += StorageManager
6 | LIBRARIES += AP_ADC
7 |
--------------------------------------------------------------------------------
/libraries/Filter/examples/LowPassFilter2p/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/Filter/keywords.txt:
--------------------------------------------------------------------------------
1 | Filter KEYWORD1
2 | FilterWithBuffer KEYWORD1
3 | ModeFilter KEYWORD1
4 | AverageFilter KEYWORD1
5 | apply KEYWORD2
6 | reset KEYWORD2
7 | get_filter_size KEYWORD2
8 | samples KEYWORD2
9 | sample_index KEYWORD2
10 |
--------------------------------------------------------------------------------
/libraries/GCS_Console/examples/Console/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/GCS_Console/examples/Console/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Mission
4 | LIBRARIES += AP_Param
5 | LIBRARIES += AP_Terrain
6 | LIBRARIES += GCS_Console
7 | LIBRARIES += GCS_MAVLink
8 | LIBRARIES += StorageManager
9 |
--------------------------------------------------------------------------------
/libraries/GCS_Console/examples/Console/nobuild.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/libraries/GCS_Console/examples/Console/nobuild.txt
--------------------------------------------------------------------------------
/libraries/GCS_Console/examples/Console/simplegcs.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 |
3 | #include
4 |
5 | void send_heartbeat(mavlink_channel_t chan);
6 | bool try_send_message(mavlink_channel_t chan, int msgid);
7 | bool try_send_statustext(mavlink_channel_t chan, const char *text, int len);
8 |
9 | void simplegcs_update(mavlink_channel_t chan);
10 | void handle_message(mavlink_channel_t chan, mavlink_message_t* msg);
11 |
--------------------------------------------------------------------------------
/libraries/GCS_Console/examples/Console/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | # TODO: Test code doesn't build. Fix or delete the test.
6 | return
7 |
8 | bld.ap_example(
9 | use='ap',
10 | )
11 |
--------------------------------------------------------------------------------
/libraries/GCS_MAVLink/.gitignore:
--------------------------------------------------------------------------------
1 | *~
2 | doc/html
3 | doc/*.log
4 |
5 | include/mavlink/v0.9/slugs/
6 | include/mavlink/v0.9/ualberta/
7 | include/mavlink/v0.9/minimal/
8 | include/mavlink/v0.9/test/
9 | include/mavlink/v0.9/pixhawk/
10 |
11 | include/mavlink/v1.0/slugs/
12 | include/mavlink/v1.0/ualberta/
13 | include/mavlink/v1.0/minimal/
14 | include/mavlink/v1.0/test/
15 | include/mavlink/v1.0/pixhawk/
16 | include/mavlink/v1.0/sensoar/
17 |
--------------------------------------------------------------------------------
/libraries/GCS_MAVLink/examples/routing/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/GCS_MAVLink/examples/routing/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/PID/examples/pid/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/PID/examples/pid/make.inc:
--------------------------------------------------------------------------------
1 | LIBRARIES += AP_Common
2 | LIBRARIES += AP_Math
3 | LIBRARIES += AP_Param
4 | LIBRARIES += PID
5 | LIBRARIES += StorageManager
6 | LIBRARIES += AP_ADC
7 | LIBRARIES += GCS_MAVLink
8 | LIBRARIES += DataFlash
9 |
--------------------------------------------------------------------------------
/libraries/PID/examples/pid/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/PID/keywords.txt:
--------------------------------------------------------------------------------
1 | PID KEYWORD1
2 | get_pid KEYWORD2
3 | reset_I KEYWORD2
4 | kP KEYWORD2
5 | kD KEYWORD2
6 | kI KEYWORD2
7 | imax KEYWORD2
8 | load_gains KEYWORD2
9 | save_gains KEYWORD2
10 |
--------------------------------------------------------------------------------
/libraries/RC_Channel/examples/RC_Channel/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/RC_Channel/examples/RC_Channel/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/RC_Channel/examples/RC_UART/Makefile:
--------------------------------------------------------------------------------
1 | BOARD = mega
2 | include ../../../../mk/apm.mk
3 |
--------------------------------------------------------------------------------
/libraries/RC_Channel/examples/RC_UART/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/libraries/StorageManager/examples/StorageTest/Makefile:
--------------------------------------------------------------------------------
1 | include ../../../../mk/apm.mk
2 |
--------------------------------------------------------------------------------
/libraries/StorageManager/examples/StorageTest/wscript:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # encoding: utf-8
3 |
4 | def build(bld):
5 | bld.ap_example(
6 | use='ap',
7 | )
8 |
--------------------------------------------------------------------------------
/mk/PX4/ROMFS/firmware/oreoled.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/ROMFS/firmware/oreoled.bin
--------------------------------------------------------------------------------
/mk/PX4/ROMFS/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | tone_alarm MNCC
4 |
5 | if [ $HAVE_RGBLED == 1 ]
6 | then
7 | rgbled rgb 16 0 0
8 | fi
9 |
10 | nshterm /dev/ttyACM0 &
11 | sleep 1
12 | nshterm /dev/ttyS0 &
13 | sleep 1
14 | exit
15 |
--------------------------------------------------------------------------------
/mk/PX4/ROMFS/tones/startup:
--------------------------------------------------------------------------------
1 | MFMST200L64O4ceceP32ceceP8df#df#P32df#df#P8L16gf#g>c
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/README.md:
--------------------------------------------------------------------------------
1 | These tools are from the ros project. You can find the master sources
2 | here:
3 |
4 | http://github.com/ros/gencpp
5 | http://github.com/ros/genmsg
6 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/gencpp/.gitignore:
--------------------------------------------------------------------------------
1 | *.pyc
2 | ._*
3 | *~
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/gencpp/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(gencpp)
3 | find_package(catkin REQUIRED COMPONENTS genmsg)
4 |
5 | catkin_package(
6 | CATKIN_DEPENDS genmsg
7 | CFG_EXTRAS gencpp-extras.cmake
8 | )
9 |
10 | add_subdirectory(scripts)
11 |
12 | file(WRITE ${CATKIN_DEVEL_PREFIX}/${GENMSG_LANGS_DESTINATION}/gencpp "C++")
13 | install(FILES ${CATKIN_DEVEL_PREFIX}/${GENMSG_LANGS_DESTINATION}/gencpp
14 | DESTINATION ${GENMSG_LANGS_DESTINATION})
15 |
16 | catkin_python_setup()
17 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/gencpp/rosdoc.yaml:
--------------------------------------------------------------------------------
1 | - builder: sphinx
2 | sphinx_root_dir: doc
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/gencpp/scripts/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | install(
2 | FILES msg.h.template srv.h.template
3 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
4 |
5 | catkin_install_python(
6 | PROGRAMS gen_cpp.py
7 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
8 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/gencpp/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | from distutils.core import setup
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 | d = generate_distutils_setup(
7 | packages=['gencpp'],
8 | package_dir={'': 'src'},
9 | requires=['genmsg']
10 | )
11 |
12 | setup(**d)
13 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/.gitignore:
--------------------------------------------------------------------------------
1 | *.pyc
2 | ._*
3 | *~
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/.hgignore:
--------------------------------------------------------------------------------
1 | syntax: glob
2 | *.orig
3 | *.swp
4 | *.pyc
5 | *.DS_Store
6 | *~
7 | *.log
8 | MANIFEST
9 | .coverage
10 | nosetests.xml
11 | syntax: regexp
12 | (target|build|dist)/.*
13 |
14 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/cmake/pkg-genmsg.context.in:
--------------------------------------------------------------------------------
1 | # generated from genmsg/cmake/pkg-genmsg.context.in
2 |
3 | messages_str = "@ARG_MESSAGES@"
4 | services_str = "@ARG_SERVICES@"
5 | pkg_name = "@PROJECT_NAME@"
6 | dependencies_str = "@ARG_DEPENDENCIES@"
7 | langs = "@GEN_LANGS@"
8 | dep_include_paths_str = "@MSG_INCLUDE_DIRS@"
9 | PYTHON_EXECUTABLE = "@PYTHON_EXECUTABLE@"
10 | package_has_static_sources = '@package_has_static_sources@' == 'TRUE'
11 | genmsg_check_deps_script = "@GENMSG_CHECK_DEPS_SCRIPT@"
12 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/cmake/pkg-msg-extras.cmake.in:
--------------------------------------------------------------------------------
1 | set(@PROJECT_NAME@_MESSAGE_FILES "@PKG_MSG_FILES@")
2 | set(@PROJECT_NAME@_SERVICE_FILES "@PKG_SRV_FILES@")
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/cmake/pkg-msg-paths.cmake.develspace.in:
--------------------------------------------------------------------------------
1 | # generated from genmsg/cmake/pkg-msg-paths.cmake.develspace.in
2 |
3 | set(@PROJECT_NAME@_MSG_INCLUDE_DIRS "@PKG_MSG_INCLUDE_DIRS@")
4 | set(@PROJECT_NAME@_MSG_DEPENDENCIES @ARG_DEPENDENCIES@)
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/cmake/pkg-msg-paths.cmake.installspace.in:
--------------------------------------------------------------------------------
1 | # generated from genmsg/cmake/pkg-msg-paths.cmake.installspace.in
2 |
3 | _prepend_path("${@PROJECT_NAME@_DIR}/.." "@PKG_MSG_INCLUDE_DIRS@" @PROJECT_NAME@_MSG_INCLUDE_DIRS UNIQUE)
4 | set(@PROJECT_NAME@_MSG_DEPENDENCIES @ARG_DEPENDENCIES@)
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/doc/python_api.rst:
--------------------------------------------------------------------------------
1 | genmsg Python API
2 | =================
3 |
4 | .. module:: genmsg
5 |
6 | Classes
7 | -------
8 |
9 | .. autoclass:: MsgSpec
10 | :members:
11 |
12 | .. autoclass:: SrvSpec
13 | :members:
14 |
15 | .. autoclass:: Constant
16 | :members:
17 |
18 | .. autoclass:: Field
19 | :members:
20 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/doc/ros.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/Tools/genmsg/doc/ros.png
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/rosdoc.yaml:
--------------------------------------------------------------------------------
1 | - builder: sphinx
2 | sphinx_root_dir: doc
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | from distutils.core import setup
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 | d = generate_distutils_setup(
7 | packages=['genmsg'],
8 | package_dir={'': 'src'}
9 | )
10 |
11 | setup(**d)
12 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/Tools/genmsg/test/__init__.py
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Point.msg:
--------------------------------------------------------------------------------
1 | # This contains the position of a point in free space
2 | float64 x
3 | float64 y
4 | float64 z
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Point32.msg:
--------------------------------------------------------------------------------
1 | # This contains the position of a point in free space(with 32 bits of precision).
2 | # It is recommeded to use Point wherever possible instead of Point32.
3 | #
4 | # This recommendation is to promote interoperability.
5 | #
6 | # This message is designed to take up less space when sending
7 | # lots of points at once, as in the case of a PointCloud.
8 |
9 | float32 x
10 | float32 y
11 | float32 z
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PointStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Point with reference coordinate frame and timestamp
2 | Header header
3 | Point point
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Polygon.msg:
--------------------------------------------------------------------------------
1 | #A specification of a polygon where the first and last points are assumed to be connected
2 | geometry_msgs/Point32[] points
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PolygonStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Polygon with reference coordinate frame and timestamp
2 | Header header
3 | Polygon polygon
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Pose.msg:
--------------------------------------------------------------------------------
1 | # A representation of pose in free space, composed of position and orientation.
2 | Point position
3 | Quaternion orientation
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Pose2D.msg:
--------------------------------------------------------------------------------
1 | # This expresses a position and orientation on a 2D manifold.
2 |
3 | float64 x
4 | float64 y
5 | float64 theta
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PoseArray.msg:
--------------------------------------------------------------------------------
1 | # An array of poses with a header for global reference.
2 |
3 | Header header
4 |
5 | geometry_msgs/Pose[] poses
6 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PoseStamped.msg:
--------------------------------------------------------------------------------
1 | # A Pose with reference coordinate frame and timestamp
2 | Header header
3 | Pose pose
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PoseWithCovariance.msg:
--------------------------------------------------------------------------------
1 | # This represents a pose in free space with uncertainty.
2 |
3 | Pose pose
4 |
5 | # Row-major representation of the 6x6 covariance matrix
6 | # The orientation parameters use a fixed-axis representation.
7 | # In order, the parameters are:
8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
9 | float64[36] covariance
10 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/PoseWithCovarianceStamped.msg:
--------------------------------------------------------------------------------
1 | # This expresses an estimated pose with a reference coordinate frame and timestamp
2 |
3 | Header header
4 | PoseWithCovariance pose
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Quaternion.msg:
--------------------------------------------------------------------------------
1 | # This represents an orientation in free space in quaternion form.
2 |
3 | float64 x
4 | float64 y
5 | float64 z
6 | float64 w
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/QuaternionStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents an orientation with reference coordinate frame and timestamp.
2 |
3 | Header header
4 | Quaternion quaternion
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Transform.msg:
--------------------------------------------------------------------------------
1 | # This represents the transform between two coordinate frames in free space.
2 |
3 | Vector3 translation
4 | Quaternion rotation
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/TransformStamped.msg:
--------------------------------------------------------------------------------
1 | # This expresses a transform from coordinate frame header.frame_id
2 | # to the coordinate frame child_frame_id
3 | #
4 | # This message is mostly used by the
5 | # tf package.
6 | # See it's documentation for more information.
7 |
8 | Header header
9 | string child_frame_id # the frame id of the child frame
10 | Transform transform
11 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Twist.msg:
--------------------------------------------------------------------------------
1 | # This expresses velocity in free space broken into it's linear and angular parts.
2 | Vector3 linear
3 | Vector3 angular
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/TwistStamped.msg:
--------------------------------------------------------------------------------
1 | # A twist with reference coordinate frame and timestamp
2 | Header header
3 | Twist twist
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/TwistWithCovariance.msg:
--------------------------------------------------------------------------------
1 | # This expresses velocity in free space with uncertianty.
2 |
3 | Twist twist
4 |
5 | # Row-major representation of the 6x6 covariance matrix
6 | # The orientation parameters use a fixed-axis representation.
7 | # In order, the parameters are:
8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
9 | float64[36] covariance
10 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/TwistWithCovarianceStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents an estimate twist with reference coordinate frame and timestamp.
2 | Header header
3 | TwistWithCovariance twist
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Vector3.msg:
--------------------------------------------------------------------------------
1 | # This represents a vector in free space.
2 |
3 | float64 x
4 | float64 y
5 | float64 z
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Vector3Stamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Vector3 with reference coordinate frame and timestamp
2 | Header header
3 | Vector3 vector
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/Wrench.msg:
--------------------------------------------------------------------------------
1 | # This represents force in free space, separated into
2 | # it's linear and angular parts.
3 | Vector3 force
4 | Vector3 torque
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/geometry_msgs/msg/WrenchStamped.msg:
--------------------------------------------------------------------------------
1 | # A wrench with reference coordinate frame and timestamp
2 | Header header
3 | Wrench wrench
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/invalid/msg/BadDepend.msg:
--------------------------------------------------------------------------------
1 | std_msgs/NonExistent data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/invalid/msg/BadLocalDepend.msg:
--------------------------------------------------------------------------------
1 | NonExistent data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/rosgraph_msgs/msg/Clock.msg:
--------------------------------------------------------------------------------
1 | # roslib/Clock is used for publishing simulated time in ROS.
2 | # This message simply communicates the current time.
3 | # For more information, see http://www.ros.org/wiki/Clock
4 | time clock
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/rosgraph_msgs/msg/Log.msg:
--------------------------------------------------------------------------------
1 | ##
2 | ## Severity level constants
3 | ##
4 | byte DEBUG=1 #debug level
5 | byte INFO=2 #general level
6 | byte WARN=4 #warning level
7 | byte ERROR=8 #error level
8 | byte FATAL=16 #fatal/critical level
9 | ##
10 | ## Fields
11 | ##
12 | Header header
13 | byte level
14 | string name # name of the node
15 | string msg # message
16 | string file # file the message came from
17 | string function # function the message came from
18 | uint32 line # line the message came from
19 | string[] topics # topic names that the node publishes
20 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/sensor_msgs/msg/Joy.msg:
--------------------------------------------------------------------------------
1 | # Reports the state of a joysticks axes and buttons.
2 | Header header # timestamp in the header is the time the data is received from the joystick
3 | float32[] axes # the axes measurements from a joystick
4 | int32[] buttons # the buttons measurements from a joystick
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/sensor_msgs/msg/JoyFeedback.msg:
--------------------------------------------------------------------------------
1 | # Declare of the type of feedback
2 | uint8 TYPE_LED = 0
3 | uint8 TYPE_RUMBLE = 1
4 | uint8 TYPE_BUZZER = 2
5 |
6 | uint8 type
7 |
8 | # This will hold an id number for each type of each feedback.
9 | # Example, the first led would be id=0, the second would be id=1
10 | uint8 id
11 |
12 | # Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is
13 | # actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.
14 | float32 intensity
15 |
16 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/sensor_msgs/msg/JoyFeedbackArray.msg:
--------------------------------------------------------------------------------
1 | # This message publishes values for multiple feedback at once.
2 | JoyFeedback[] array
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/sensor_msgs/msg/PointField.msg:
--------------------------------------------------------------------------------
1 | # This message holds the description of one point entry in the
2 | # PointCloud2 message format.
3 | uint8 INT8 = 1
4 | uint8 UINT8 = 2
5 | uint8 INT16 = 3
6 | uint8 UINT16 = 4
7 | uint8 INT32 = 5
8 | uint8 UINT32 = 6
9 | uint8 FLOAT32 = 7
10 | uint8 FLOAT64 = 8
11 |
12 | string name # Name of field
13 | uint32 offset # Offset from start of point struct
14 | uint8 datatype # Datatype enumeration, see above
15 | uint32 count # How many elements in the field
16 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Bool.msg:
--------------------------------------------------------------------------------
1 | bool data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/ColorRGBA.msg:
--------------------------------------------------------------------------------
1 | float32 r
2 | float32 g
3 | float32 b
4 | float32 a
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Duration.msg:
--------------------------------------------------------------------------------
1 | duration data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Empty.msg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Empty.msg
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Float32.msg:
--------------------------------------------------------------------------------
1 | float32 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Float32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | float32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Float64.msg:
--------------------------------------------------------------------------------
1 | float64 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Float64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | float64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Header.msg:
--------------------------------------------------------------------------------
1 | # Standard metadata for higher-level stamped data types.
2 | # This is generally used to communicate timestamped data
3 | # in a particular coordinate frame.
4 | #
5 | # sequence ID: consecutively increasing ID
6 | uint32 seq
7 | #Two-integer timestamp that is expressed as:
8 | # * stamp.secs: seconds (stamp_secs) since epoch
9 | # * stamp.nsecs: nanoseconds since stamp_secs
10 | # time-handling sugar is provided by the client library
11 | time stamp
12 | #Frame this data is associated with
13 | # 0: no frame
14 | # 1: global frame
15 | string frame_id
16 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int16.msg:
--------------------------------------------------------------------------------
1 | int16 data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int16MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int16[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int32.msg:
--------------------------------------------------------------------------------
1 | int32 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int64.msg:
--------------------------------------------------------------------------------
1 | int64 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int8.msg:
--------------------------------------------------------------------------------
1 | int8 data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Int8MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int8[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/MultiArrayDimension.msg:
--------------------------------------------------------------------------------
1 | string label # label of given dimension
2 | uint32 size # size of given dimension (in type units)
3 | uint32 stride # stride of given dimension
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/String.msg:
--------------------------------------------------------------------------------
1 | string data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/Time.msg:
--------------------------------------------------------------------------------
1 | time data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt16.msg:
--------------------------------------------------------------------------------
1 | uint16 data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt16MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint16[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt32.msg:
--------------------------------------------------------------------------------
1 | uint32 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt64.msg:
--------------------------------------------------------------------------------
1 | uint64 data
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt8.msg:
--------------------------------------------------------------------------------
1 | uint8 data
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_msgs/msg/UInt8MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint8[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/std_srvs/srv/Empty.srv:
--------------------------------------------------------------------------------
1 | ---
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/test_ros/msg/Bad.msg:
--------------------------------------------------------------------------------
1 | ;lkjasdfl;k l;kajdf;lkasjdff
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/test_ros/msg/TestString.msg:
--------------------------------------------------------------------------------
1 | # Integration test message
2 | # caller_id of most recent node to send this message
3 | string caller_id
4 | # caller_id of the original node to send this message
5 | string orig_caller_id
6 | string data
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/test_ros/srv/AddTwoInts.srv:
--------------------------------------------------------------------------------
1 | int64 a
2 | int64 b
3 | ---
4 | int64 sum
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/files/test_ros/srv/GetPoseStamped.srv:
--------------------------------------------------------------------------------
1 | ---
2 | geometry_msgs/PoseStamped pose
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/constants1.txt:
--------------------------------------------------------------------------------
1 | int32 x=1
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/constants2.txt:
--------------------------------------------------------------------------------
1 | int32 x=2
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/constants3.txt:
--------------------------------------------------------------------------------
1 | int32 x=10
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/constantsB1.txt:
--------------------------------------------------------------------------------
1 | # protect against aliasing
2 | string s=u
3 | int32 a
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/constantsB2.txt:
--------------------------------------------------------------------------------
1 | # protect against aliasing
2 | string s=uint32 a
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/fields1.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | int32 b
3 | int32 c
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/fields2.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | int32 b
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/fields3.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | int32 b
3 | int32 c
4 | int32 d
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/fields4.txt:
--------------------------------------------------------------------------------
1 | int32 a1
2 | int32 b
3 | int32 c
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/different/fields5.txt:
--------------------------------------------------------------------------------
1 | uint32 a
2 | int32 b
3 | int32 c
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constant1.txt:
--------------------------------------------------------------------------------
1 | int32 x=123456
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constant2.txt:
--------------------------------------------------------------------------------
1 | int32 x = 123456
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constant3.txt:
--------------------------------------------------------------------------------
1 | #x is a value
2 | int32 x=123456 #a constant
3 | #i'm done
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constantB1.txt:
--------------------------------------------------------------------------------
1 | string foo="#bar
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constantB2.txt:
--------------------------------------------------------------------------------
1 | #blah
2 | string foo ="#bar
3 | #b
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constantC1.txt:
--------------------------------------------------------------------------------
1 | int32 x=123
2 | int32 y=234
3 | int32 z=345
4 | float32 a=1.0
5 | float32 b=2.0
6 | float32 pi=3.14159
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/constantC2.txt:
--------------------------------------------------------------------------------
1 | int32 x = 123
2 | int32 y = 234
3 | int32 z = 345
4 | float32 a= 1.0
5 | float32 b= 2.0
6 | float32 pi = 3.14159
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/embed1.txt:
--------------------------------------------------------------------------------
1 | acffd30cd6b6de30f120938c17c593fb log
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/embed2.txt:
--------------------------------------------------------------------------------
1 | rosgraph_msgs/Log log
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/embed3.txt:
--------------------------------------------------------------------------------
1 | #commented
2 | rosgraph_msgs/Log log
3 | #another comment
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/embed4.txt:
--------------------------------------------------------------------------------
1 | #comment. note the stripped package name
2 | Log log
3 |
4 | #comment
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/empty1.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/Tools/genmsg/test/md5tests/md5text/empty1.txt
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/empty2.txt:
--------------------------------------------------------------------------------
1 |
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/empty3.txt:
--------------------------------------------------------------------------------
1 | ### Just a comment
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/empty4.txt:
--------------------------------------------------------------------------------
1 | # A comment
2 |
3 | # With multiple lines
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/field1.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/field2.txt:
--------------------------------------------------------------------------------
1 | #comment before
2 | int32 field
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/field3.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 | #comment after
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/field4.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/field5.txt:
--------------------------------------------------------------------------------
1 | int32 field #field does something
2 |
3 |
4 |
5 | #the end
6 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/multi1.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | acffd30cd6b6de30f120938c17c593fb log
3 | string s
4 | a9c97c1d230cfc112e270351a944ee47 time
5 | int32 b
6 | duration d
7 | time t
8 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/multi2.txt:
--------------------------------------------------------------------------------
1 | # comment about a
2 | int32 a
3 | # comment about log
4 | rosgraph_msgs/Log log
5 | # comment about s
6 | string s
7 | # comment about time
8 | rosgraph_msgs/Clock time
9 | # comment about b
10 | int32 b
11 | # comment about d
12 | duration d
13 | # comment about t
14 | time t
15 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/multi3.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | Log log
3 | string s
4 | Clock time
5 | int32 b
6 | duration d
7 | time t
8 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/multi4.txt:
--------------------------------------------------------------------------------
1 | # short comment about a
2 | int32 a #a
3 | # short comment about log
4 | Log log #log
5 | #
6 | # short comment about s
7 | string s #s
8 | # short comment about time
9 | Clock time #time
10 | # short comment about b
11 | int32 b #b
12 | # short comment about d
13 | duration d #d
14 | # short comment about t
15 | time t # t
16 |
17 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/md5text/multi5.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | rosgraph_msgs/Log log
3 |
4 | string s
5 | rosgraph_msgs/Clock time
6 | int32 b
7 | duration d
8 | time t
9 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constant1.txt:
--------------------------------------------------------------------------------
1 | int32 x=123456
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constant2.txt:
--------------------------------------------------------------------------------
1 | int32 x = 123456
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constant3.txt:
--------------------------------------------------------------------------------
1 | #x is a value
2 | int32 x=123456 #a constant
3 | #i'm done
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constantB1.txt:
--------------------------------------------------------------------------------
1 | string foo="#bar
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constantB2.txt:
--------------------------------------------------------------------------------
1 | #blah
2 | string foo ="#bar
3 | #b
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constantC1.txt:
--------------------------------------------------------------------------------
1 | int32 x=123
2 | int32 y=234
3 | int32 z=345
4 | float32 a=1.0
5 | float32 b=2.0
6 | float32 pi=3.14159
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/constantC2.txt:
--------------------------------------------------------------------------------
1 | int32 x = 123
2 | int32 y = 234
3 | int32 z = 345
4 | float32 a= 1.0
5 | float32 b= 2.0
6 | float32 pi = 3.14159
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/embed1.txt:
--------------------------------------------------------------------------------
1 | rosgraph_msgs/Log log
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/embed2.txt:
--------------------------------------------------------------------------------
1 | Log log
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/embed3.txt:
--------------------------------------------------------------------------------
1 | #commented
2 | rosgraph_msgs/Log log
3 | #another comment
4 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/embed4.txt:
--------------------------------------------------------------------------------
1 | #comment. note the stripped package name
2 | Log log
3 |
4 | #comment
5 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/empty1.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/Tools/genmsg/test/md5tests/same/empty1.txt
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/empty2.txt:
--------------------------------------------------------------------------------
1 |
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/empty3.txt:
--------------------------------------------------------------------------------
1 | ### Just a comment
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/empty4.txt:
--------------------------------------------------------------------------------
1 | # A comment
2 |
3 | # With multiple lines
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/field1.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/field2.txt:
--------------------------------------------------------------------------------
1 | #comment before
2 | int32 field
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/field3.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 | #comment after
3 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/field4.txt:
--------------------------------------------------------------------------------
1 | int32 field
2 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/field5.txt:
--------------------------------------------------------------------------------
1 | int32 field #field does something
2 |
3 |
4 |
5 | #the end
6 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/multi1.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | rosgraph_msgs/Log log
3 | string s
4 | rosgraph_msgs/Clock time
5 | int32 b
6 | duration d
7 | time t
8 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/multi2.txt:
--------------------------------------------------------------------------------
1 | # comment about a
2 | int32 a
3 | # comment about log
4 | rosgraph_msgs/Log log
5 | # comment about s
6 | string s
7 | # comment about time
8 | rosgraph_msgs/Clock time
9 | # comment about b
10 | int32 b
11 | # comment about d
12 | duration d
13 | # comment about t
14 | time t
15 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/multi3.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | Log log
3 | string s
4 | Clock time
5 | int32 b
6 | duration d
7 | time t
8 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/multi4.txt:
--------------------------------------------------------------------------------
1 | # short comment about a
2 | int32 a #a
3 | # short comment about log
4 | Log log #log
5 | #
6 | # short comment about s
7 | string s #s
8 | # short comment about time
9 | Clock time #time
10 | # short comment about b
11 | int32 b #b
12 | # short comment about d
13 | duration d #d
14 | # short comment about t
15 | time t # t
16 |
17 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/md5tests/same/multi5.txt:
--------------------------------------------------------------------------------
1 | int32 a
2 | rosgraph_msgs/Log log
3 |
4 | string s
5 | rosgraph_msgs/Clock time
6 | int32 b
7 | duration d
8 | time t
9 |
--------------------------------------------------------------------------------
/mk/PX4/Tools/genmsg/test/test_genmsg_base.py:
--------------------------------------------------------------------------------
1 | def test_log():
2 | from genmsg.base import log
3 | log("hello", "there")
4 |
5 | def test_plog():
6 | class Foo(object):
7 | pass
8 | from genmsg.base import plog
9 | plog("hello", Foo())
10 |
11 | def test_exceptions():
12 | from genmsg import InvalidMsgSpec
13 | try:
14 | raise InvalidMsgSpec('hello')
15 | except InvalidMsgSpec:
16 | pass
17 |
--------------------------------------------------------------------------------
/mk/PX4/bootloader/README.txt:
--------------------------------------------------------------------------------
1 | These FMU and FMUv2 bootloader images are built from:
2 |
3 | https://github.com/PX4/Bootloader
4 |
5 | They are in ROMFS to make it easier for users to update their
6 | bootloaders using:
7 |
8 | bl_update /etc/bootloader/fmu_bl.bin
9 |
10 | from a nsh prompt. Users can get a nsh prompt either via the CLI in
11 | test -> shell, or by booting with no SD card installed
12 |
13 | to use NSH to do this, please see the Wiki http://dev.ardupilot.org/wiki/interfacing-with-pixhawk-using-the-nsh
14 |
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4fmu_bl.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4fmu_bl.bin
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4fmuv2_bl.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4fmuv2_bl.bin
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4fmuv2_bl.elf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4fmuv2_bl.elf
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4fmuv4_bl.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4fmuv4_bl.bin
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4io_bl.bin:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4io_bl.bin
--------------------------------------------------------------------------------
/mk/PX4/bootloader/px4io_bl.elf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/3drobotics/ardupilot/f9b0ed80d173ebf4e0e7ad9bbc6ab178679a1e8c/mk/PX4/bootloader/px4io_bl.elf
--------------------------------------------------------------------------------
/mk/PX4/config_px4fmu-v1_APM.mk:
--------------------------------------------------------------------------------
1 | #
2 | # Makefile for the px4fmu-v1_APM configuration
3 | #
4 | include $(SKETCHBOOK)/mk/PX4/px4_common.mk
5 |
6 | MODULES += drivers/boards/px4fmu-v1
7 | MODULES += drivers/px4io
8 | MODULES += drivers/px4flow
9 |
--------------------------------------------------------------------------------
/mk/PX4/config_px4fmu-v2_APM.mk:
--------------------------------------------------------------------------------
1 | #
2 | # Makefile for the px4fmu-v2_APM configuration
3 | #
4 | include $(SKETCHBOOK)/mk/PX4/px4_common.mk
5 |
6 | MODULES += drivers/lsm303d
7 | MODULES += drivers/l3gd20
8 | MODULES += drivers/mpu9250
9 | MODULES += drivers/boards/px4fmu-v2
10 | MODULES += drivers/pwm_input
11 | MODULES += modules/uavcan
12 | MODULES += lib/mathlib
13 | MODULES += drivers/px4io
14 | MODULES += drivers/px4flow
15 | MODULES += drivers/oreoled
16 | MODULES += drivers/oreoled/oreoled_bootloader
17 |
--------------------------------------------------------------------------------
/mk/PX4/config_px4fmu-v4_APM.mk:
--------------------------------------------------------------------------------
1 | #
2 | # Makefile for the px4fmu-v4_APM configuration
3 | #
4 | include $(SKETCHBOOK)/mk/PX4/px4_common.mk
5 |
6 | MODULES += drivers/mpu9250
7 | MODULES += drivers/boards/px4fmu-v4
8 | MODULES += drivers/pwm_input
9 | MODULES += modules/uavcan
10 | MODULES += lib/mathlib
11 |
--------------------------------------------------------------------------------
/mk/VRBRAIN/ROMFS_VRBRAIN45_APM/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | nshterm /dev/ttyACM0 &
4 | sleep 1
5 | nshterm /dev/ttyS0 &
6 | sleep 1
7 | exit
8 |
--------------------------------------------------------------------------------
/mk/VRBRAIN/ROMFS_VRBRAIN51_APM/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | nshterm /dev/ttyACM0 &
4 | sleep 1
5 | nshterm /dev/ttyS0 &
6 | sleep 1
7 | exit
8 |
--------------------------------------------------------------------------------
/mk/VRBRAIN/ROMFS_VRBRAIN52_APM/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | nshterm /dev/ttyACM0 &
4 | sleep 1
5 | nshterm /dev/ttyS0 &
6 | sleep 1
7 | exit
8 |
--------------------------------------------------------------------------------
/mk/VRBRAIN/ROMFS_VRUBRAIN51_APM/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | nshterm /dev/ttyACM0 &
4 | sleep 1
5 | nshterm /dev/ttyS0 &
6 | sleep 1
7 | exit
8 |
--------------------------------------------------------------------------------
/mk/VRBRAIN/ROMFS_VRUBRAIN52_APM/init.d/rc.error:
--------------------------------------------------------------------------------
1 | echo "Error in startup"
2 |
3 | nshterm /dev/ttyACM0 &
4 | sleep 1
5 | nshterm /dev/ttyS0 &
6 | sleep 1
7 | exit
8 |
--------------------------------------------------------------------------------
/mk/board_linux.mk:
--------------------------------------------------------------------------------
1 | TOOLCHAIN = NATIVE
2 |
3 | include $(MK_DIR)/find_tools.mk
4 |
5 | # Linux build is just the same as SITL for now
6 | LIBS = -lm -pthread -lrt
7 | include $(MK_DIR)/board_native.mk
8 | include $(MK_DIR)/upload_firmware.mk
9 |
--------------------------------------------------------------------------------
/mk/board_px4.mk:
--------------------------------------------------------------------------------
1 | TOOLCHAIN = NATIVE
2 | include $(MK_DIR)/find_tools.mk
3 | include $(MK_DIR)/px4_targets.mk
4 |
--------------------------------------------------------------------------------
/mk/board_vrbrain.mk:
--------------------------------------------------------------------------------
1 | TOOLCHAIN = NATIVE
2 | include $(MK_DIR)/find_tools.mk
3 | include $(MK_DIR)/vrbrain_targets.mk
4 |
--------------------------------------------------------------------------------
/mk/configure.mk:
--------------------------------------------------------------------------------
1 | configure:
2 | @echo "make configure is no longer required"
3 |
--------------------------------------------------------------------------------
/mk/upload_firmware.mk:
--------------------------------------------------------------------------------
1 | ifneq ($(BOARD_LINUX_HOST),)
2 | upload: $(SKETCHELF).timestamp-upload
3 |
4 | $(SKETCHELF).timestamp-upload: $(SKETCHELF)
5 | scp $(SKETCHELF) $(BOARD_LINUX_HOST):
6 | touch $@
7 | else
8 | upload:
9 | @echo Check your config.mk: BOARD_LINUX_HOST should be defined to upload firmware
10 | exit 1
11 | endif
12 |
--------------------------------------------------------------------------------
/tests/AP_gtest.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Utility header for unit tests with gtest.
3 | */
4 | #include
5 |
6 |
7 | #define AP_GTEST_PRINTATBLE_PARAM_MEMBER(class_name_, printable_member_) \
8 | ::std::ostream& operator<<(::std::ostream& os, const class_name_& param) \
9 | { \
10 | return os << param.printable_member_; \
11 | }
12 |
13 | #define AP_GTEST_MAIN() \
14 | int main(int argc, char *argv[]) \
15 | { \
16 | ::testing::InitGoogleTest(&argc, argv); \
17 | return RUN_ALL_TESTS(); \
18 | }
19 |
--------------------------------------------------------------------------------