Browse Source

Merge working changes into export-build branch.

sbg
px4dev 12 years ago
parent
commit
01e427b17c
  1. 4
      .gitignore
  2. 37
      Makefile
  3. 67
      ROMFS/px4fmu_common/init.d/rc.FMU_quad_x
  4. 80
      ROMFS/px4fmu_common/init.d/rc.PX4IO
  5. 98
      ROMFS/px4fmu_common/init.d/rc.PX4IOAR
  6. 66
      ROMFS/px4fmu_common/init.d/rc.boarddetect
  7. 10
      ROMFS/px4fmu_common/init.d/rc.jig
  8. 9
      ROMFS/px4fmu_common/init.d/rc.logging
  9. 34
      ROMFS/px4fmu_common/init.d/rc.sensors
  10. 13
      ROMFS/px4fmu_common/init.d/rc.standalone
  11. 79
      ROMFS/px4fmu_common/init.d/rcS
  12. 0
      ROMFS/px4fmu_common/logging/logconv.m
  13. 0
      ROMFS/px4fmu_common/mixers/FMU_AERT.mix
  14. 0
      ROMFS/px4fmu_common/mixers/FMU_AET.mix
  15. 0
      ROMFS/px4fmu_common/mixers/FMU_Q.mix
  16. 0
      ROMFS/px4fmu_common/mixers/FMU_RET.mix
  17. 0
      ROMFS/px4fmu_common/mixers/FMU_X5.mix
  18. 0
      ROMFS/px4fmu_common/mixers/FMU_delta.mix
  19. 0
      ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
  20. 0
      ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
  21. 0
      ROMFS/px4fmu_common/mixers/FMU_octo_+.mix
  22. 0
      ROMFS/px4fmu_common/mixers/FMU_octo_x.mix
  23. 0
      ROMFS/px4fmu_common/mixers/FMU_pass.mix
  24. 0
      ROMFS/px4fmu_common/mixers/FMU_quad_+.mix
  25. 0
      ROMFS/px4fmu_common/mixers/FMU_quad_x.mix
  26. 0
      ROMFS/px4fmu_common/mixers/README
  27. 679
      Tools/px_uploader.py
  28. 57
      apps/attitude_estimator_ekf/Makefile
  29. 0
      apps/commander/.context
  30. 45
      apps/commander/Makefile
  31. 41
      apps/drivers/boards/px4fmu/Makefile
  32. 44
      apps/drivers/px4fmu/Makefile
  33. 2
      apps/sensors/sensors.cpp
  34. 45
      apps/systemcmds/eeprom/Makefile
  35. 2
      makefiles/board_px4fmu.mk
  36. 2
      makefiles/board_px4io.mk
  37. 28
      makefiles/config_px4fmu_default.mk
  38. 65
      makefiles/firmware.mk
  39. 34
      makefiles/module.mk
  40. 7
      makefiles/nuttx.mk
  41. 34
      makefiles/setup.mk
  42. 1
      makefiles/toolchain_gnu-arm-eabi.mk
  43. 6
      makefiles/upload.mk
  44. 6
      nuttx/configs/px4fmu/include/board.h
  45. 7
      nuttx/configs/px4fmu/nsh/appconfig
  46. 2
      nuttx/configs/px4fmu/nsh/defconfig
  47. 0
      src/drivers/ardrone_interface/ardrone_interface.c
  48. 0
      src/drivers/ardrone_interface/ardrone_motor_control.c
  49. 0
      src/drivers/ardrone_interface/ardrone_motor_control.h
  50. 12
      src/drivers/ardrone_interface/module.mk
  51. 9
      src/drivers/boards/px4fmu/module.mk
  52. 5
      src/drivers/boards/px4fmu/px4fmu_can.c
  53. 37
      src/drivers/boards/px4fmu/px4fmu_init.c
  54. 7
      src/drivers/boards/px4fmu/px4fmu_internal.h
  55. 0
      src/drivers/boards/px4fmu/px4fmu_led.c
  56. 0
      src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
  57. 18
      src/drivers/boards/px4fmu/px4fmu_spi.c
  58. 0
      src/drivers/boards/px4fmu/px4fmu_usb.c
  59. 0
      src/drivers/l3gd20/l3gd20.cpp
  60. 6
      src/drivers/l3gd20/module.mk
  61. 0
      src/drivers/px4fmu/fmu.cpp
  62. 6
      src/drivers/px4fmu/module.mk
  63. 62
      src/include/visibility.h
  64. 0
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
  65. 0
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
  66. 0
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
  67. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter.c
  68. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter.h
  69. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.c
  70. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.h
  71. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.c
  72. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.h
  73. 0
      src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_types.h
  74. 0
      src/modules/attitude_estimator_ekf/codegen/cross.c
  75. 0
      src/modules/attitude_estimator_ekf/codegen/cross.h
  76. 0
      src/modules/attitude_estimator_ekf/codegen/eye.c
  77. 0
      src/modules/attitude_estimator_ekf/codegen/eye.h
  78. 0
      src/modules/attitude_estimator_ekf/codegen/mrdivide.c
  79. 0
      src/modules/attitude_estimator_ekf/codegen/mrdivide.h
  80. 0
      src/modules/attitude_estimator_ekf/codegen/norm.c
  81. 0
      src/modules/attitude_estimator_ekf/codegen/norm.h
  82. 0
      src/modules/attitude_estimator_ekf/codegen/rdivide.c
  83. 0
      src/modules/attitude_estimator_ekf/codegen/rdivide.h
  84. 0
      src/modules/attitude_estimator_ekf/codegen/rtGetInf.c
  85. 0
      src/modules/attitude_estimator_ekf/codegen/rtGetInf.h
  86. 0
      src/modules/attitude_estimator_ekf/codegen/rtGetNaN.c
  87. 0
      src/modules/attitude_estimator_ekf/codegen/rtGetNaN.h
  88. 0
      src/modules/attitude_estimator_ekf/codegen/rt_defines.h
  89. 0
      src/modules/attitude_estimator_ekf/codegen/rt_nonfinite.c
  90. 0
      src/modules/attitude_estimator_ekf/codegen/rt_nonfinite.h
  91. 0
      src/modules/attitude_estimator_ekf/codegen/rtwtypes.h
  92. 16
      src/modules/attitude_estimator_ekf/module.mk
  93. 0
      src/modules/commander/calibration_routines.c
  94. 0
      src/modules/commander/calibration_routines.h
  95. 0
      src/modules/commander/commander.c
  96. 0
      src/modules/commander/commander.h
  97. 13
      src/modules/commander/module.mk
  98. 0
      src/modules/commander/state_machine_helper.c
  99. 0
      src/modules/commander/state_machine_helper.h
  100. 0
      src/systemcmds/eeprom/24xxxx_mtd.c
  101. Some files were not shown because too many files have changed in this diff Show More

4
.gitignore vendored

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
.built
.context
*.context
*.bdat
*.pdat
@ -56,3 +57,6 @@ core @@ -56,3 +57,6 @@ core
mkdeps
Archives
Build
!ROMFS/*/*.d
!ROMFS/*/*/*.d
!ROMFS/*/*/*/*.d

37
Makefile

@ -42,12 +42,12 @@ include $(PX4_BASE)makefiles/setup.mk @@ -42,12 +42,12 @@ include $(PX4_BASE)makefiles/setup.mk
#
# Canned firmware configurations that we build.
#
CONFIGS ?= px4fmu_default px4io_default
CONFIGS ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
#
# Boards that we build NuttX export kits for.
#
BOARDS = px4fmu px4io
BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
#
# Debugging
@ -62,11 +62,26 @@ MQUIET = --no-print-directory @@ -62,11 +62,26 @@ MQUIET = --no-print-directory
#
# If the user has listed a config as a target, strip it out and override CONFIGS.
#
FIRMWARE_GOAL = firmware
EXPLICIT_CONFIGS := $(filter $(CONFIGS),$(MAKECMDGOALS))
ifneq ($(EXPLICIT_CONFIGS),)
CONFIGS := $(EXPLICIT_CONFIGS)
.PHONY: $(EXPLICIT_CONFIGS)
$(EXPLICIT_CONFIGS): all
#
# If the user has asked to upload, they must have also specified exactly one
# config.
#
ifneq ($(filter upload,$(MAKECMDGOALS)),)
ifneq ($(words $(EXPLICIT_CONFIGS)),1)
$(error In order to upload, exactly one board config must be specified)
endif
FIRMWARE_GOAL = upload
.PHONY: upload
upload:
@:
endif
endif
#
@ -95,11 +110,11 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: @@ -95,11 +110,11 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
@echo %%%% Building $(config) in $(work_dir)
@echo %%%%
$(Q) mkdir -p $(work_dir)
$(Q) make -C $(work_dir) \
$(Q) make -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
firmware
$(FIRMWARE_GOAL)
#
# Build the NuttX export archives.
@ -118,15 +133,21 @@ NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export) @@ -118,15 +133,21 @@ NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
.PHONY: archives
archives: $(NUTTX_ARCHIVES)
# We cannot build these parallel; note that we also force -j1 for the
# sub-make invocations.
ifneq ($(filter archives,$(MAKECMDGOALS)),)
.NOTPARALLEL:
endif
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
$(ARCHIVE_DIR)%.export: configuration = $(if $(filter $(board),px4io),io,nsh)
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
@echo %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@echo %% Exporting NuttX for $(board)
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) export
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
$(Q) mkdir -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
@ -162,9 +183,7 @@ help: @@ -162,9 +183,7 @@ help:
@echo ""
@echo " all"
@echo " Build all firmware configs: $(CONFIGS)"
@echo " A limited set of configs can be built with:"
@echo ""
@echo " CONFIGS=<list-of-configs>"
@echo " A limited set of configs can be built with CONFIGS=<list-of-configs>"
@echo ""
@for config in $(CONFIGS); do \
echo " $$config"; \

67
ROMFS/px4fmu_common/init.d/rc.FMU_quad_x

@ -0,0 +1,67 @@ @@ -0,0 +1,67 @@
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE custom
echo "[init] doing PX4FMU Quad startup..."
#
# Start the ORB
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Start attitude control
#
multirotor_att_control start
echo "[init] startup done, exiting"
exit

80
ROMFS/px4fmu_common/init.d/rc.PX4IO

@ -0,0 +1,80 @@ @@ -0,0 +1,80 @@
#!nsh
# Disable USB and autostart
set USB no
set MODE camflyer
#
# Start the ORB
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start GPS interface
#
gps start
#
# Start the attitude estimator
#
kalman_demo start
#
# Start PX4IO interface
#
px4io start
#
# Load mixer and start controllers
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
#
# Start logging
#
sdlog start -s 10
#
# Start system state
#
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi

98
ROMFS/px4fmu_common/init.d/rc.PX4IOAR

@ -0,0 +1,98 @@ @@ -0,0 +1,98 @@
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE ardrone
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
#
uorb start
#
# Init the parameter storage
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the multi rotor attitude controller
#
multirotor_att_control start
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start GPS capture
#
gps start
#
# Start logging
#
sdlog start -s 10
#
# Start system state
#
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
#
echo "[init] startup done"
exit

66
ROMFS/px4fmu_common/init.d/rc.boarddetect

@ -0,0 +1,66 @@ @@ -0,0 +1,66 @@
#!nsh
#
# If we are still in flight mode, work out what airframe
# configuration we have and start up accordingly.
#
if [ $MODE != autostart ]
then
echo "[init] automatic startup cancelled by user script"
else
echo "[init] detecting attached hardware..."
#
# Assume that we are PX4FMU in standalone mode
#
set BOARD PX4FMU
#
# Are we attached to a PX4IOAR (AR.Drone carrier board)?
#
if boardinfo test name PX4IOAR
then
set BOARD PX4IOAR
if [ -f /etc/init.d/rc.PX4IOAR ]
then
echo "[init] reading /etc/init.d/rc.PX4IOAR"
usleep 500
sh /etc/init.d/rc.PX4IOAR
fi
else
echo "[init] PX4IOAR not detected"
fi
#
# Are we attached to a PX4IO?
#
if boardinfo test name PX4IO
then
set BOARD PX4IO
if [ -f /etc/init.d/rc.PX4IO ]
then
echo "[init] reading /etc/init.d/rc.PX4IO"
usleep 500
sh /etc/init.d/rc.PX4IO
fi
else
echo "[init] PX4IO not detected"
fi
#
# Looks like we are stand-alone
#
if [ $BOARD == PX4FMU ]
then
echo "[init] no expansion board detected"
if [ -f /etc/init.d/rc.standalone ]
then
echo "[init] reading /etc/init.d/rc.standalone"
sh /etc/init.d/rc.standalone
fi
fi
#
# We may not reach here if the airframe-specific script exits the shell.
#
echo "[init] startup done."
fi

10
ROMFS/px4fmu_common/init.d/rc.jig

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!nsh
#
# Test jig startup script
#
echo "[testing] doing production test.."
tests jig
echo "[testing] testing done"

9
ROMFS/px4fmu_common/init.d/rc.logging

@ -0,0 +1,9 @@ @@ -0,0 +1,9 @@
#!nsh
#
# Initialise logging services.
#
if [ -d /fs/microsd ]
then
sdlog start
fi

34
ROMFS/px4fmu_common/init.d/rc.sensors

@ -0,0 +1,34 @@ @@ -0,0 +1,34 @@
#!nsh
#
# Standard startup script for PX4FMU onboard sensor drivers.
#
#
# Start sensor drivers here.
#
ms5611 start
adc start
if mpu6000 start
then
echo "using MPU6000 and HMC5883L"
hmc5883 start
else
echo "using L3GD20 and LSM303D"
l3gd20 start
lsm303 start
fi
#
# Start the sensor collection task.
# IMPORTANT: this also loads param offsets
# ALWAYS start this task before the
# preflight_check.
#
sensors start
#
# Check sensors - run AFTER 'sensors start'
#
preflight_check

13
ROMFS/px4fmu_common/init.d/rc.standalone

@ -0,0 +1,13 @@ @@ -0,0 +1,13 @@
#!nsh
#
# Flight startup script for PX4FMU standalone configuration.
#
echo "[init] doing standalone PX4FMU startup..."
#
# Start the ORB
#
uorb start
echo "[init] startup done"

79
ROMFS/px4fmu_common/init.d/rcS

@ -0,0 +1,79 @@ @@ -0,0 +1,79 @@
#!nsh
#
# PX4FMU startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Start playing the startup tune
#
tone_alarm start
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
else
echo "[init] no microSD card found"
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
# if this is an APM build then there will be a rc.APM script
# from an EXTERNAL_SCRIPTS build option
if [ -f /etc/init.d/rc.APM ]
then
echo Running rc.APM
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi

0
ROMFS/px4fmu_default/logging/logconv.m → ROMFS/px4fmu_common/logging/logconv.m

0
ROMFS/px4fmu_default/mixers/FMU_AERT.mix → ROMFS/px4fmu_common/mixers/FMU_AERT.mix

0
ROMFS/px4fmu_default/mixers/FMU_AET.mix → ROMFS/px4fmu_common/mixers/FMU_AET.mix

0
ROMFS/px4fmu_default/mixers/FMU_Q.mix → ROMFS/px4fmu_common/mixers/FMU_Q.mix

0
ROMFS/px4fmu_default/mixers/FMU_RET.mix → ROMFS/px4fmu_common/mixers/FMU_RET.mix

0
ROMFS/px4fmu_default/mixers/FMU_X5.mix → ROMFS/px4fmu_common/mixers/FMU_X5.mix

0
ROMFS/px4fmu_default/mixers/FMU_delta.mix → ROMFS/px4fmu_common/mixers/FMU_delta.mix

0
ROMFS/px4fmu_default/mixers/FMU_hex_+.mix → ROMFS/px4fmu_common/mixers/FMU_hex_+.mix

0
ROMFS/px4fmu_default/mixers/FMU_hex_x.mix → ROMFS/px4fmu_common/mixers/FMU_hex_x.mix

0
ROMFS/px4fmu_default/mixers/FMU_octo_+.mix → ROMFS/px4fmu_common/mixers/FMU_octo_+.mix

0
ROMFS/px4fmu_default/mixers/FMU_octo_x.mix → ROMFS/px4fmu_common/mixers/FMU_octo_x.mix

0
ROMFS/px4fmu_default/mixers/FMU_pass.mix → ROMFS/px4fmu_common/mixers/FMU_pass.mix

0
ROMFS/px4fmu_default/mixers/FMU_quad_+.mix → ROMFS/px4fmu_common/mixers/FMU_quad_+.mix

0
ROMFS/px4fmu_default/mixers/FMU_quad_x.mix → ROMFS/px4fmu_common/mixers/FMU_quad_x.mix

0
ROMFS/px4fmu_default/mixers/README → ROMFS/px4fmu_common/mixers/README

679
Tools/px_uploader.py

@ -41,20 +41,19 @@ @@ -41,20 +41,19 @@
# The uploader uses the following fields from the firmware file:
#
# image
# The firmware that will be uploaded.
# The firmware that will be uploaded.
# image_size
# The size of the firmware in bytes.
# The size of the firmware in bytes.
# board_id
# The board for which the firmware is intended.
# The board for which the firmware is intended.
# board_revision
# Currently only used for informational purposes.
# Currently only used for informational purposes.
#
import sys
import argparse
import binascii
import serial
import os
import struct
import json
import zlib
@ -64,292 +63,294 @@ import array @@ -64,292 +63,294 @@ import array
from sys import platform as _platform
class firmware(object):
'''Loads a firmware file'''
desc = {}
image = bytes()
crctab = array.array('I', [
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d ])
crcpad = bytearray('\xff\xff\xff\xff')
def __init__(self, path):
# read the file
f = open(path, "r")
self.desc = json.load(f)
f.close()
self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
# pad image to 4-byte length
while ((len(self.image) % 4) != 0):
self.image.append('\xff')
def property(self, propname):
return self.desc[propname]
def __crc32(self, bytes, state):
for byte in bytes:
index = (state ^ byte) & 0xff
state = self.crctab[index] ^ (state >> 8)
return state
def crc(self, padlen):
state = self.__crc32(self.image, int(0))
for i in range(len(self.image), (padlen - 1), 4):
state = self.__crc32(self.crcpad, state)
return state
'''Loads a firmware file'''
desc = {}
image = bytes()
crctab = array.array('I', [
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d])
crcpad = bytearray('\xff\xff\xff\xff')
def __init__(self, path):
# read the file
f = open(path, "r")
self.desc = json.load(f)
f.close()
self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
# pad image to 4-byte length
while ((len(self.image) % 4) != 0):
self.image.append('\xff')
def property(self, propname):
return self.desc[propname]
def __crc32(self, bytes, state):
for byte in bytes:
index = (state ^ byte) & 0xff
state = self.crctab[index] ^ (state >> 8)
return state
def crc(self, padlen):
state = self.__crc32(self.image, int(0))
for i in range(len(self.image), (padlen - 1), 4):
state = self.__crc32(self.crcpad, state)
return state
class uploader(object):
'''Uploads a firmware file to the PX FMU bootloader'''
# protocol bytes
INSYNC = chr(0x12)
EOC = chr(0x20)
# reply bytes
OK = chr(0x10)
FAILED = chr(0x11)
INVALID = chr(0x13) # rev3+
# command bytes
NOP = chr(0x00) # guaranteed to be discarded by the bootloader
GET_SYNC = chr(0x21)
GET_DEVICE = chr(0x22)
CHIP_ERASE = chr(0x23)
CHIP_VERIFY = chr(0x24) # rev2 only
PROG_MULTI = chr(0x27)
READ_MULTI = chr(0x28) # rev2 only
GET_CRC = chr(0x29) # rev3+
REBOOT = chr(0x30)
INFO_BL_REV = chr(1) # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 3 # maximum supported bootloader protocol
INFO_BOARD_ID = chr(2) # board type
INFO_BOARD_REV = chr(3) # board revision
INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
self.port = serial.Serial(portname, baudrate, timeout=0.25)
def close(self):
if self.port is not None:
self.port.close()
def __send(self, c):
# print("send " + binascii.hexlify(c))
self.port.write(str(c))
def __recv(self, count = 1):
c = self.port.read(count)
if len(c) < 1:
raise RuntimeError("timeout waiting for data")
# print("recv " + binascii.hexlify(c))
return c
def __recv_int(self):
raw = self.__recv(4)
val = struct.unpack("<I", raw)
return val[0]
def __getSync(self):
self.port.flush()
c = self.__recv()
if c is not self.INSYNC:
raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if c == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if c != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
# attempt to get back into sync with the bootloader
def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput()
self.__send(uploader.GET_SYNC
+ uploader.EOC)
self.__getSync()
# def __trySync(self):
# c = self.__recv()
# if (c != self.INSYNC):
# #print("unexpected 0x%x instead of INSYNC" % ord(c))
# return False;
# c = self.__recv()
# if (c != self.OK):
# #print("unexpected 0x%x instead of OK" % ord(c))
# return False
# return True
# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
self.__send(uploader.GET_DEVICE + param + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self):
self.__send(uploader.CHIP_ERASE
+ uploader.EOC)
# erase is very slow, give it 10s
deadline = time.time() + 10
while time.time() < deadline:
try:
self.__getSync()
return
except RuntimeError as ex:
# we timed out, that's OK
continue
raise RuntimeError("timed out waiting for erase")
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data):
self.__send(uploader.PROG_MULTI
+ chr(len(data)))
self.__send(data)
self.__send(uploader.EOC)
self.__getSync()
# verify multiple bytes in flash
def __verify_multi(self, data):
self.__send(uploader.READ_MULTI
+ chr(len(data))
+ uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
print(("got " + binascii.hexlify(programmed)))
print(("expect " + binascii.hexlify(data)))
return False
self.__getSync()
return True
# send the reboot command
def __reboot(self):
self.__send(uploader.REBOOT
+ uploader.EOC)
self.port.flush()
# v3+ can report failure if the first word flash fails
if self.bl_rev >= 3:
self.__getSync()
# split a sequence into a list of size-constrained pieces
def __split_len(self, seq, length):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# upload code
def __program(self, fw):
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
for bytes in groups:
self.__program_multi(bytes)
# verify code
def __verify_v2(self, fw):
self.__send(uploader.CHIP_VERIFY
+ uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
for bytes in groups:
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
def __verify_v3(self, fw):
expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC
+ uploader.EOC)
report_crc = self.__recv_int()
self.__getSync()
if report_crc != expect_crc:
print(("Expected 0x%x" % expect_crc))
print(("Got 0x%x" % report_crc))
raise RuntimeError("Program CRC failed")
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
self.__sync()
# get the bootloader protocol ID first
self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
print(("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV))
raise RuntimeError("Bootloader protocol mismatch")
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
# upload the firmware
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
raise RuntimeError("Firmware not suitable for this board (run 'make configure_px4fmu && make clean' or 'make configure_px4io && make clean' to reconfigure).")
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
print("erase...")
self.__erase()
print("program...")
self.__program(fw)
print("verify...")
if self.bl_rev == 2:
self.__verify_v2(fw)
else:
self.__verify_v3(fw)
print("done, rebooting.")
self.__reboot()
self.port.close()
'''Uploads a firmware file to the PX FMU bootloader'''
# protocol bytes
INSYNC = chr(0x12)
EOC = chr(0x20)
# reply bytes
OK = chr(0x10)
FAILED = chr(0x11)
INVALID = chr(0x13) # rev3+
# command bytes
NOP = chr(0x00) # guaranteed to be discarded by the bootloader
GET_SYNC = chr(0x21)
GET_DEVICE = chr(0x22)
CHIP_ERASE = chr(0x23)
CHIP_VERIFY = chr(0x24) # rev2 only
PROG_MULTI = chr(0x27)
READ_MULTI = chr(0x28) # rev2 only
GET_CRC = chr(0x29) # rev3+
REBOOT = chr(0x30)
INFO_BL_REV = chr(1) # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 3 # maximum supported bootloader protocol
INFO_BOARD_ID = chr(2) # board type
INFO_BOARD_REV = chr(3) # board revision
INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
self.port = serial.Serial(portname, baudrate, timeout=0.5)
def close(self):
if self.port is not None:
self.port.close()
def __send(self, c):
# print("send " + binascii.hexlify(c))
self.port.write(str(c))
def __recv(self, count=1):
c = self.port.read(count)
if len(c) < 1:
raise RuntimeError("timeout waiting for data")
# print("recv " + binascii.hexlify(c))
return c
def __recv_int(self):
raw = self.__recv(4)
val = struct.unpack("<I", raw)
return val[0]
def __getSync(self):
self.port.flush()
c = self.__recv()
if c is not self.INSYNC:
raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if c == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if c != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
# attempt to get back into sync with the bootloader
def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput()
self.__send(uploader.GET_SYNC
+ uploader.EOC)
self.__getSync()
# def __trySync(self):
# c = self.__recv()
# if (c != self.INSYNC):
# #print("unexpected 0x%x instead of INSYNC" % ord(c))
# return False;
# c = self.__recv()
# if (c != self.OK):
# #print("unexpected 0x%x instead of OK" % ord(c))
# return False
# return True
# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
self.__send(uploader.GET_DEVICE + param + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self):
self.__send(uploader.CHIP_ERASE
+ uploader.EOC)
# erase is very slow, give it 20s
deadline = time.time() + 20
while time.time() < deadline:
try:
self.__getSync()
return
except RuntimeError:
# we timed out, that's OK
continue
raise RuntimeError("timed out waiting for erase")
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data):
self.__send(uploader.PROG_MULTI
+ chr(len(data)))
self.__send(data)
self.__send(uploader.EOC)
self.__getSync()
# verify multiple bytes in flash
def __verify_multi(self, data):
self.__send(uploader.READ_MULTI
+ chr(len(data))
+ uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
print("got " + binascii.hexlify(programmed))
print("expect " + binascii.hexlify(data))
return False
self.__getSync()
return True
# send the reboot command
def __reboot(self):
self.__send(uploader.REBOOT
+ uploader.EOC)
self.port.flush()
# v3+ can report failure if the first word flash fails
if self.bl_rev >= 3:
self.__getSync()
# split a sequence into a list of size-constrained pieces
def __split_len(self, seq, length):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# upload code
def __program(self, fw):
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
for bytes in groups:
self.__program_multi(bytes)
# verify code
def __verify_v2(self, fw):
self.__send(uploader.CHIP_VERIFY
+ uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
for bytes in groups:
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
def __verify_v3(self, fw):
expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC
+ uploader.EOC)
report_crc = self.__recv_int()
self.__getSync()
if report_crc != expect_crc:
print("Expected 0x%x" % expect_crc)
print("Got 0x%x" % report_crc)
raise RuntimeError("Program CRC failed")
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
self.__sync()
# get the bootloader protocol ID first
self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
print("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV)
raise RuntimeError("Bootloader protocol mismatch")
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
# upload the firmware
def upload(self, fw):
# Make sure we are doing the right thing
if self.board_type != fw.property('board_id'):
raise RuntimeError("Firmware not suitable for this board")
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
print("erase...")
self.__erase()
print("program...")
self.__program(fw)
print("verify...")
if self.bl_rev == 2:
self.__verify_v2(fw)
else:
self.__verify_v3(fw)
print("done, rebooting.")
self.__reboot()
self.port.close()
# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
@ -360,57 +361,57 @@ args = parser.parse_args() @@ -360,57 +361,57 @@ args = parser.parse_args()
# Load the firmware file
fw = firmware(args.firmware)
print(("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'))))
print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision')))
# Spin waiting for a device to show up
while True:
for port in args.port.split(","):
#print("Trying %s" % port)
# create an uploader attached to the port
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if not "COM" in port and not "tty.usb" in port:
up = uploader(port, args.baud)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
if not "COM" in port and not "ACM" in port:
up = uploader(port, args.baud)
elif "win" in _platform:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
except:
# open failed, rate-limit our attempts
time.sleep(0.05)
# and loop to the next port
continue
# port is open, try talking to it
try:
# identify the bootloader
up.identify()
print(("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port)))
except:
# most probably a timeout talking to the port, no bootloader
continue
try:
# ok, we have a bootloader, try flashing it
up.upload(fw)
except RuntimeError as ex:
# print the error
print(("ERROR: %s" % ex.args))
finally:
# always close the port
up.close()
# we could loop here if we wanted to wait for more boards...
sys.exit(0)
for port in args.port.split(","):
#print("Trying %s" % port)
# create an uploader attached to the port
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if not "COM" in port and not "tty.usb" in port:
up = uploader(port, args.baud)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
if not "COM" in port and not "ACM" in port:
up = uploader(port, args.baud)
elif "win" in _platform:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
except:
# open failed, rate-limit our attempts
time.sleep(0.05)
# and loop to the next port
continue
# port is open, try talking to it
try:
# identify the bootloader
up.identify()
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
except:
# most probably a timeout talking to the port, no bootloader
continue
try:
# ok, we have a bootloader, try flashing it
up.upload(fw)
except RuntimeError as ex:
# print the error
print("ERROR: %s" % ex.args)
finally:
# always close the port
up.close()
# we could loop here if we wanted to wait for more boards...
sys.exit(0)

57
apps/attitude_estimator_ekf/Makefile

@ -1,57 +0,0 @@ @@ -1,57 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
APPNAME = attitude_estimator_ekf
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
CXXSRCS = attitude_estimator_ekf_main.cpp
CSRCS = attitude_estimator_ekf_params.c \
codegen/eye.c \
codegen/attitudeKalmanfilter.c \
codegen/mrdivide.c \
codegen/rdivide.c \
codegen/attitudeKalmanfilter_initialize.c \
codegen/attitudeKalmanfilter_terminate.c \
codegen/rt_nonfinite.c \
codegen/rtGetInf.c \
codegen/rtGetNaN.c \
codegen/norm.c \
codegen/cross.c
# XXX this is *horribly* broken
INCLUDES += $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

0
apps/commander/.context

45
apps/commander/Makefile

@ -1,45 +0,0 @@ @@ -1,45 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Commander application
#
APPNAME = commander
PRIORITY = SCHED_PRIORITY_MAX - 30
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
include $(APPDIR)/mk/app.mk

41
apps/drivers/boards/px4fmu/Makefile

@ -1,41 +0,0 @@ @@ -1,41 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Board-specific startup code for the PX4FMU
#
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
LIBNAME = brd_px4fmu
include $(APPDIR)/mk/app.mk

44
apps/drivers/px4fmu/Makefile

@ -1,44 +0,0 @@ @@ -1,44 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Interface driver for the PX4FMU board
#
APPNAME = fmu
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
include $(APPDIR)/mk/app.mk

2
apps/sensors/sensors.cpp

@ -372,7 +372,9 @@ Sensors *g_sensors; @@ -372,7 +372,9 @@ Sensors *g_sensors;
}
Sensors::Sensors() :
#ifdef CONFIG_HRT_PPM
_ppm_last_valid(0),
#endif
_fd_adc(-1),
_last_adc(0),

45
apps/systemcmds/eeprom/Makefile

@ -1,45 +0,0 @@ @@ -1,45 +0,0 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build the eeprom tool.
#
APPNAME = eeprom
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
MAXOPTIMIZATION = -Os
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

2
makefiles/board_px4fmu.mk

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
#
# Platform-specific definitions for the PX4FMU
# Board-specific definitions for the PX4FMU
#
#

2
makefiles/board_px4io.mk

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
#
# Platform-specific definitions for the PX4IO
# Board-specific definitions for the PX4IO
#
#

28
makefiles/config_px4fmu_default.mk

@ -5,7 +5,26 @@ @@ -5,7 +5,26 @@
#
# Use the configuration's ROMFS.
#
ROMFS_ROOT = $(PX4_BASE)/ROMFS/$(CONFIG)
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
#
# Board support modules
#
MODULES += drivers/px4fmu
MODULES += drivers/boards/px4fmu
MODULES += drivers/l3gd20
MODULES += drivers/ardrone_interface
MODULES += systemcmds/eeprom
#
# General system control
#
MODULES += modules/commander
#
# Estimation modules (EKF / other filters)
#
#MODULES += modules/attitude_estimator_ekf
#
# Transitional support - add commands from the NuttX export archive.
@ -22,25 +41,19 @@ endef @@ -22,25 +41,19 @@ endef
# command priority stack entrypoint
BUILTIN_COMMANDS := \
$(call _B, adc, , 2048, adc_main ) \
$(call _B, ardrone_interface, SCHED_PRIORITY_MAX-15, 2048, ardrone_interface_main ) \
$(call _B, attitude_estimator_ekf, , 2048, attitude_estimator_ekf_main) \
$(call _B, bl_update, , 4096, bl_update_main ) \
$(call _B, blinkm, , 2048, blinkm_main ) \
$(call _B, bma180, , 2048, bma180_main ) \
$(call _B, boardinfo, , 2048, boardinfo_main ) \
$(call _B, commander, SCHED_PRIORITY_MAX-30, 2048, commander_main ) \
$(call _B, control_demo, , 2048, control_demo_main ) \
$(call _B, delay_test, , 2048, delay_test_main ) \
$(call _B, eeprom, , 4096, eeprom_main ) \
$(call _B, fixedwing_att_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_att_control_main ) \
$(call _B, fixedwing_pos_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_pos_control_main ) \
$(call _B, fmu, , 2048, fmu_main ) \
$(call _B, gps, , 2048, gps_main ) \
$(call _B, hil, , 2048, hil_main ) \
$(call _B, hmc5883, , 4096, hmc5883_main ) \
$(call _B, hott_telemetry, , 2048, hott_telemetry_main ) \
$(call _B, kalman_demo, SCHED_PRIORITY_MAX-30, 2048, kalman_demo_main ) \
$(call _B, l3gd20, , 2048, l3gd20_main ) \
$(call _B, math_demo, , 8192, math_demo_main ) \
$(call _B, mavlink, , 2048, mavlink_main ) \
$(call _B, mavlink_onboard, , 2048, mavlink_onboard_main ) \
@ -62,4 +75,5 @@ BUILTIN_COMMANDS := \ @@ -62,4 +75,5 @@ BUILTIN_COMMANDS := \
$(call _B, tests, , 12000, tests_main ) \
$(call _B, tone_alarm, , 2048, tone_alarm_main ) \
$(call _B, top, SCHED_PRIORITY_DEFAULT-10, 3000, top_main ) \
$(call _B, param, SCHED_PRIORITY_DEFAULT-10, 2048, param_main ) \
$(call _B, uorb, , 4096, uorb_main )

65
makefiles/firmware.mk

@ -64,7 +64,16 @@ @@ -64,7 +64,16 @@
# path to this file.
#
# CONFIG:
# Used to set the output filename; defaults to 'firmware'.
# Used when searching for the configuration file, and available
# to module Makefiles to select optional features.
# If not set, CONFIG_FILE must be set and CONFIG will be derived
# automatically from it.
#
# CONFIG_FILE:
# If set, overrides the configuration file search logic. Sets
# CONFIG to the name of the configuration file, strips any
# leading config_ prefix and any suffix. e.g. config_board_foo.mk
# results in CONFIG being set to 'board_foo'.
#
# WORK_DIR:
# Sets the directory in which the firmware will be built. Defaults
@ -92,11 +101,14 @@ @@ -92,11 +101,14 @@
# If PX4_BASE wasn't set previously, work out what it should be
# and set it here now.
#
MK_DIR ?= $(dir $(lastword $(MAKEFILE_LIST)))
MK_DIR ?= $(dir $(lastword $(MAKEFILE_LIST)))
ifeq ($(PX4_BASE),)
export PX4_BASE := $(abspath $(MK_DIR)/..)
endif
$(info % PX4_BASE = $(PX4_BASE))
ifneq ($(words $(PX4_BASE)),1)
$(error Cannot build when the PX4_BASE path contains one or more space characters.)
endif
#
# Set a default target so that included makefiles or errors here don't
@ -115,13 +127,14 @@ include $(MK_DIR)/setup.mk @@ -115,13 +127,14 @@ include $(MK_DIR)/setup.mk
#
# Locate the configuration file
#
ifneq ($(CONFIG_FILE),)
CONFIG := $(subst config_,,$(basename $(notdir $(CONFIG_FILE))))
else
CONFIG_FILE := $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk)
endif
ifeq ($(CONFIG),)
$(error Missing configuration name or file (specify with CONFIG=<config>))
endif
CONFIG_FILE := $(firstword $(wildcard $(CONFIG)) $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk))
ifeq ($(CONFIG_FILE),)
$(error Can't find a config file called $(CONFIG) or $(PX4_MK_DIR)/config_$(CONFIG).mk)
endif
export CONFIG
include $(CONFIG_FILE)
$(info % CONFIG = $(CONFIG))
@ -211,10 +224,7 @@ MODULE_OBJS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)module @@ -211,10 +224,7 @@ MODULE_OBJS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)module
$(MODULE_OBJS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
$(MODULE_OBJS): mkfile = $(patsubst %module.pre.o,%module.mk,$(relpath))
$(MODULE_OBJS): $(GLOBAL_DEPS) $(NUTTX_CONFIG_HEADER)
@$(ECHO) %%
@$(ECHO) %% Building module using $(mkfile)
@$(ECHO) %%
$(Q) $(MAKE) -f $(PX4_MK_DIR)module.mk \
$(Q) $(MAKE) -r -f $(PX4_MK_DIR)module.mk \
MODULE_WORK_DIR=$(dir $@) \
MODULE_OBJ=$@ \
MODULE_MK=$(mkfile) \
@ -230,7 +240,7 @@ $(MODULE_CLEANS): relpath = $(patsubst $(WORK_DIR)%,%,$@) @@ -230,7 +240,7 @@ $(MODULE_CLEANS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
$(MODULE_CLEANS): mkfile = $(patsubst %clean,%module.mk,$(relpath))
$(MODULE_CLEANS):
@$(ECHO) %% cleaning using $(mkfile)
$(Q) $(MAKE) -f $(PX4_MK_DIR)module.mk \
$(Q) $(MAKE) -r -f $(PX4_MK_DIR)module.mk \
MODULE_WORK_DIR=$(dir $@) \
MODULE_MK=$(mkfile) \
clean
@ -246,6 +256,9 @@ include $(PX4_MK_DIR)/nuttx.mk @@ -246,6 +256,9 @@ include $(PX4_MK_DIR)/nuttx.mk
################################################################################
ifneq ($(ROMFS_ROOT),)
ifeq ($(wildcard $(ROMFS_ROOT)),)
$(error ROMFS_ROOT specifies a directory that does not exist)
endif
#
# Note that there is no support for more than one root directory or constructing
@ -272,7 +285,7 @@ $(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS) @@ -272,7 +285,7 @@ $(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
# Generate the ROMFS image from the root
$(ROMFS_IMG): $(ROMFS_DEPS) $(GLOBAL_DEPS)
@$(ECHO) %% generating $@
@$(ECHO) "ROMFS: $@"
$(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
@ -298,10 +311,12 @@ endif @@ -298,10 +311,12 @@ endif
#
BUILTIN_CSRC = $(WORK_DIR)builtin_commands.c
# add command definitions from modules
BUILTIN_COMMAND_FILES := $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)
BUILTIN_COMMANDS += $(subst COMMAND.,,$(notdir $(BUILTIN_COMMAND_FILES)))
# command definitions from modules (may be empty at Makefile parsing time...)
MODULE_COMMANDS = $(subst COMMAND.,,$(notdir $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)))
# We must have at least one pre-defined builtin command in order to generate
# any of this.
#
ifneq ($(BUILTIN_COMMANDS),)
# (BUILTIN_PROTO,<cmdspec>,<outputfile>)
@ -315,17 +330,19 @@ define BUILTIN_DEF @@ -315,17 +330,19 @@ define BUILTIN_DEF
endef
# Don't generate until modules have updated their command files
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(BUILTIN_COMMAND_FILES)
@$(ECHO) %% generating $@
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES)
@$(ECHO) "CMDS: $@"
$(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
$(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
$(Q) $(ECHO) '#include <nuttx/binfmt/builtin.h>' >> $@
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
$(Q) $(ECHO) 'const struct builtin_s g_builtins[] = {' >> $@
$(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
$(Q) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
$(Q) $(ECHO) ' {NULL, 0, 0, NULL}' >> $@
$(Q) $(ECHO) '};' >> $@
$(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS));' >> $@
$(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS) $(MODULE_COMMANDS));' >> $@
SRCS += $(BUILTIN_CSRC)
@ -358,7 +375,7 @@ endif @@ -358,7 +375,7 @@ endif
#
PRODUCT_BUNDLE = $(WORK_DIR)firmware.px4
PRODUCT_BIN = $(WORK_DIR)firmware.bin
PRODUCT_SYM = $(WORK_DIR)firmware.sym
PRODUCT_ELF = $(WORK_DIR)firmware.elf
.PHONY: firmware
firmware: $(PRODUCT_BUNDLE)
@ -393,10 +410,10 @@ $(PRODUCT_BUNDLE): $(PRODUCT_BIN) @@ -393,10 +410,10 @@ $(PRODUCT_BUNDLE): $(PRODUCT_BIN)
--git_identity $(PX4_BASE) \
--image $< > $@
$(PRODUCT_BIN): $(PRODUCT_SYM)
$(PRODUCT_BIN): $(PRODUCT_ELF)
$(call SYM_TO_BIN,$<,$@)
$(PRODUCT_SYM): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
$(PRODUCT_ELF): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
$(call LINK,$@,$(OBJS) $(MODULE_OBJS))
#
@ -407,17 +424,19 @@ $(PRODUCT_SYM): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKF @@ -407,17 +424,19 @@ $(PRODUCT_SYM): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKF
upload: $(PRODUCT_BUNDLE) $(PRODUCT_BIN)
$(Q) $(MAKE) -f $(PX4_MK_DIR)/upload.mk \
METHOD=serial \
PRODUCT=$(PRODUCT) \
CONFIG=$(CONFIG) \
BOARD=$(BOARD) \
BUNDLE=$(PRODUCT_BUNDLE) \
BIN=$(PRODUCT_BIN)
.PHONY: clean
clean: $(MODULE_CLEANS)
@$(ECHO) %% cleaning
$(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_SYM)
$(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_ELF)
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
$(Q) $(RMDIR) $(NUTTX_EXPORT_DIR)
#
# DEP_INCLUDES is defined by the toolchain include in terms of $(OBJS)
#

34
makefiles/module.mk

@ -75,6 +75,18 @@ @@ -75,6 +75,18 @@
# the list should be formatted as:
# <command>.<priority>.<stacksize>.<entrypoint>
#
# INCLUDE_DIRS (optional, must be appended)
#
# The list of directories searched for include files. If non-standard
# includes (e.g. those from another module) are required, paths to search
# can be added here.
#
# DEFAULT_VISIBILITY (optional)
#
# If not set, global symbols defined in a module will not be visible
# outside the module. Symbols that should be globally visible must be
# marked __EXPORT.
# If set, global symbols defined in a module will be globally visible.
#
#
@ -96,12 +108,7 @@ @@ -96,12 +108,7 @@
ifeq ($(MODULE_MK),)
$(error No module makefile specified)
endif
$(info % MODULE_MK = $(MODULE_MK))
#
# Get path and tool config
#
include $(PX4_BASE)/makefiles/setup.mk
$(info %% MODULE_MK = $(MODULE_MK))
#
# Get the board/toolchain config
@ -144,12 +151,25 @@ MODULE_COMMAND_FILES := $(addprefix $(WORK_DIR)/builtin_commands/COMMAND.,$(MODU @@ -144,12 +151,25 @@ MODULE_COMMAND_FILES := $(addprefix $(WORK_DIR)/builtin_commands/COMMAND.,$(MODU
$(MODULE_COMMAND_FILES): command = $(word 2,$(subst ., ,$(notdir $(@))))
$(MODULE_COMMAND_FILES): exclude = $(dir $@)COMMAND.$(command).*
$(MODULE_COMMAND_FILES): $(GLOBAL_DEPS)
@$(ECHO) COMMAND: $(command)
@$(REMOVE) -f $(exclude)
@$(MKDIR) -p $(dir $@)
@echo "CMD: $(command)"
$(Q) $(TOUCH) $@
endif
################################################################################
# Adjust compilation flags to implement EXPORT
################################################################################
ifeq ($(DEFAULT_VISIBILITY),)
DEFAULT_VISIBILITY = hidden
else
DEFAULT_VISIBILITY = default
endif
CFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
################################################################################
# Build rules
################################################################################

7
makefiles/nuttx.mk

@ -63,7 +63,10 @@ LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script @@ -63,7 +63,10 @@ LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
#
# Add directories from the NuttX export to the relevant search paths
#
INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include
INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \
$(NUTTX_EXPORT_DIR)arch/chip \
$(NUTTX_EXPORT_DIR)arch/common
LIB_DIRS += $(NUTTX_EXPORT_DIR)libs
LIBS += -lapps -lnuttx
LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \
@ -71,5 +74,5 @@ LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \ @@ -71,5 +74,5 @@ LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \
$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
@$(ECHO) %% Unpacking $(NUTTX_ARCHIVE)
$(Q) $(UNZIP) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
$(Q) $(UNZIP_CMD) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
$(Q) $(TOUCH) $@

34
makefiles/setup.mk

@ -41,7 +41,8 @@ @@ -41,7 +41,8 @@
# the number of duplicate slashes we have lying around in paths,
# and is consistent with joining the results of $(dir) and $(notdir).
#
export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src/modules)/
export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/
export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/
export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
export NUTTX_SRC = $(abspath $(PX4_BASE)/nuttx)/
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/apps)/
@ -51,24 +52,33 @@ export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/ @@ -51,24 +52,33 @@ export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/
export BUILD_DIR = $(abspath $(PX4_BASE)/Build)/
export ARCHIVE_DIR = $(abspath $(PX4_BASE)/Archives)/
#
# Default include paths
#
export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
$(PX4_INCLUDE_DIR)
# Include from legacy app/library path
export INCLUDE_DIRS += $(NUTTX_APP_SRC)
#
# Tools
#
MKFW = $(PX4_BASE)/Tools/px_mkfw.py
UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
COPY = cp
REMOVE = rm -f
RMDIR = rm -rf
GENROMFS = genromfs
TOUCH = touch
MKDIR = mkdir
ECHO = echo
UNZIP = unzip
export MKFW = $(PX4_BASE)/Tools/px_mkfw.py
export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
export COPY = cp
export REMOVE = rm -f
export RMDIR = rm -rf
export GENROMFS = genromfs
export TOUCH = touch
export MKDIR = mkdir
export ECHO = echo
export UNZIP_CMD = unzip
#
# Host-specific paths, hacks and fixups
#
SYSTYPE := $(shell uname -s)
export SYSTYPE := $(shell uname -s)
ifeq ($(SYSTYPE),Darwin)
# Eclipse may not have the toolchain on its path.

1
makefiles/toolchain_gnu-arm-eabi.mk

@ -157,6 +157,7 @@ CXXFLAGS = $(ARCHCXXFLAGS) \ @@ -157,6 +157,7 @@ CXXFLAGS = $(ARCHCXXFLAGS) \
$(INSTRUMENTATIONDEFINES) \
$(ARCHDEFINES) \
$(EXTRADEFINES) \
-DCONFIG_WCHAR_BUILTIN \
$(addprefix -I,$(INCLUDE_DIRS))
# Flags we pass to the assembler

6
makefiles/upload.mk

@ -21,11 +21,11 @@ ifeq ($(SERIAL_PORTS),) @@ -21,11 +21,11 @@ ifeq ($(SERIAL_PORTS),)
SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
endif
.PHONY: all upload-$(METHOD)-$(PRODUCT)
all: upload-$(METHOD)-$(PRODUCT)
.PHONY: all upload-$(METHOD)-$(BOARD)
all: upload-$(METHOD)-$(BOARD)
upload-serial-px4fmu: $(BUNDLE) $(UPLOADER)
@python -u $(UPLOADER) --port $(SERIAL_PORTS) $(PRODUCT_BUNDLE)
@python -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
#
# JTAG firmware uploading with OpenOCD

6
nuttx/configs/px4fmu/include/board.h

@ -308,6 +308,10 @@ @@ -308,6 +308,10 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
@ -321,6 +325,8 @@ @@ -321,6 +325,8 @@
#define PX4_SPIDEV_ACCEL 2
#define PX4_SPIDEV_MPU 3
#define PX4_SPIDEV_ACCEL_MAG 2 // external for anti vibration test
/*
* Tone alarm output
*/

7
nuttx/configs/px4fmu/nsh/appconfig

@ -65,7 +65,6 @@ CONFIGURED_APPS += systemcmds/perf @@ -65,7 +65,6 @@ CONFIGURED_APPS += systemcmds/perf
CONFIGURED_APPS += systemcmds/top
CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/pwm
CONFIGURED_APPS += systemcmds/bl_update
@ -110,20 +109,18 @@ endif @@ -110,20 +109,18 @@ endif
CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
CONFIGURED_APPS += drivers/boards/px4fmu
#CONFIGURED_APPS += drivers/boards/px4fmu
CONFIGURED_APPS += drivers/device
CONFIGURED_APPS += drivers/ms5611
CONFIGURED_APPS += drivers/hmc5883
CONFIGURED_APPS += drivers/mpu6000
CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += drivers/led
#CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
CONFIGURED_APPS += drivers/gps
CONFIGURED_APPS += drivers/mb12xx

2
nuttx/configs/px4fmu/nsh/defconfig

@ -85,7 +85,7 @@ CONFIG_ARCH_FPU=y @@ -85,7 +85,7 @@ CONFIG_ARCH_FPU=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=y

0
apps/ardrone_interface/ardrone_interface.c → src/drivers/ardrone_interface/ardrone_interface.c

0
apps/ardrone_interface/ardrone_motor_control.c → src/drivers/ardrone_interface/ardrone_motor_control.c

0
apps/ardrone_interface/ardrone_motor_control.h → src/drivers/ardrone_interface/ardrone_motor_control.h

12
apps/drivers/l3gd20/Makefile → src/drivers/ardrone_interface/module.mk

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -32,11 +32,9 @@ @@ -32,11 +32,9 @@
############################################################################
#
# Makefile to build the L3GD20 driver.
# AR.Drone motor driver
#
APPNAME = l3gd20
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MODULE_COMMAND = ardrone_interface
SRCS = ardrone_interface.c \
ardrone_motor_control.c

9
src/drivers/boards/px4fmu/module.mk

@ -0,0 +1,9 @@ @@ -0,0 +1,9 @@
#
# Board-specific startup code for the PX4FMU
#
SRCS = px4fmu_can.c \
px4fmu_init.c \
px4fmu_pwm_servo.c \
px4fmu_spi.c \
px4fmu_usb.c

5
apps/drivers/boards/px4fmu/px4fmu_can.c → src/drivers/boards/px4fmu/px4fmu_can.c

@ -37,7 +37,6 @@ @@ -37,7 +37,6 @@
* Board-specific CAN functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
@ -57,6 +56,8 @@ @@ -57,6 +56,8 @@
#include "stm32_can.h"
#include "px4fmu_internal.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
@ -139,3 +140,5 @@ int can_devinit(void) @@ -139,3 +140,5 @@ int can_devinit(void)
return OK;
}
#endif

37
apps/drivers/boards/px4fmu/px4fmu_init.c → src/drivers/boards/px4fmu/px4fmu_init.c

@ -127,6 +127,7 @@ __EXPORT void stm32_boardinitialize(void) @@ -127,6 +127,7 @@ __EXPORT void stm32_boardinitialize(void)
****************************************************************************/
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
static struct spi_dev_s *spi3;
#include <math.h>
@ -147,6 +148,11 @@ __EXPORT int nsh_archinitialize(void) @@ -147,6 +148,11 @@ __EXPORT int nsh_archinitialize(void)
{
int result;
/* configure always-on ADC pins */
stm32_configgpio(GPIO_ADC1_IN10);
stm32_configgpio(GPIO_ADC1_IN11);
/* IN12 and IN13 further below */
/* configure the high-resolution time/callout interface */
hrt_init();
@ -173,7 +179,7 @@ __EXPORT int nsh_archinitialize(void) @@ -173,7 +179,7 @@ __EXPORT int nsh_archinitialize(void)
NULL);
// initial LED state
drv_led_start();
// drv_led_start();
up_ledoff(LED_BLUE);
up_ledoff(LED_AMBER);
up_ledon(LED_BLUE);
@ -188,7 +194,7 @@ __EXPORT int nsh_archinitialize(void) @@ -188,7 +194,7 @@ __EXPORT int nsh_archinitialize(void)
return -ENODEV;
}
// Default SPI1 to 1MHz and de-assert the known chip selects.
/* Default SPI1 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi1, 10000000);
SPI_SETBITS(spi1, 8);
SPI_SETMODE(spi1, SPIDEV_MODE3);
@ -199,6 +205,28 @@ __EXPORT int nsh_archinitialize(void) @@ -199,6 +205,28 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Successfully initialized SPI port 1\r\n");
/*
* If SPI2 is enabled in the defconfig, we loose some ADC pins as chip selects.
* Keep the SPI2 init optional and conditionally initialize the ADC pins
*/
spi2 = up_spiinitialize(2);
if (!spi2) {
message("[boot] Enabling IN12/13 instead of SPI2\n");
/* no SPI2, use pins for ADC */
stm32_configgpio(GPIO_ADC1_IN12);
stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
} else {
/* Default SPI2 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi2, 10000000);
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);
SPI_SELECT(spi2, PX4_SPIDEV_GYRO, false);
SPI_SELECT(spi2, PX4_SPIDEV_ACCEL_MAG, false);
message("[boot] Initialized SPI port2 (ADC IN12/13 blocked)\n");
}
/* Get the SPI port for the microSD slot */
message("[boot] Initializing SPI port 3\n");
@ -223,10 +251,5 @@ __EXPORT int nsh_archinitialize(void) @@ -223,10 +251,5 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n");
stm32_configgpio(GPIO_ADC1_IN10);
stm32_configgpio(GPIO_ADC1_IN11);
stm32_configgpio(GPIO_ADC1_IN12);
stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
return OK;
}

7
apps/drivers/boards/px4fmu/px4fmu_internal.h → src/drivers/boards/px4fmu/px4fmu_internal.h

@ -58,9 +58,9 @@ __BEGIN_DECLS @@ -58,9 +58,9 @@ __BEGIN_DECLS
****************************************************************************************************/
/* Configuration ************************************************************************************/
#ifdef CONFIG_STM32_SPI2
# error "SPI2 is not supported on this board"
#endif
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"
//#endif
#if defined(CONFIG_STM32_CAN1)
# warning "CAN1 is not supported on this board"
@ -77,6 +77,7 @@ __BEGIN_DECLS @@ -77,6 +77,7 @@ __BEGIN_DECLS
// XXX MPU6000 DRDY?
/* SPI chip selects */
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)

0
apps/drivers/boards/px4fmu/px4fmu_led.c → src/drivers/boards/px4fmu/px4fmu_led.c

0
apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c → src/drivers/boards/px4fmu/px4fmu_pwm_servo.c

18
apps/drivers/boards/px4fmu/px4fmu_spi.c → src/drivers/boards/px4fmu/px4fmu_spi.c

@ -121,6 +121,24 @@ __EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devi @@ -121,6 +121,24 @@ __EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
return SPI_STATUS_PRESENT;
}
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
switch (devid) {
break;
default:
break;
}
}
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{

0
apps/drivers/boards/px4fmu/px4fmu_usb.c → src/drivers/boards/px4fmu/px4fmu_usb.c

0
apps/drivers/l3gd20/l3gd20.cpp → src/drivers/l3gd20/l3gd20.cpp

6
src/drivers/l3gd20/module.mk

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
#
# LSM303D accel/mag driver
#
MODULE_COMMAND = l3gd20
SRCS = l3gd20.cpp

0
apps/drivers/px4fmu/fmu.cpp → src/drivers/px4fmu/fmu.cpp

6
src/drivers/px4fmu/module.mk

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
#
# Interface driver for the PX4FMU board
#
MODULE_COMMAND = fmu
SRCS = fmu.cpp

62
src/include/visibility.h

@ -0,0 +1,62 @@ @@ -0,0 +1,62 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file visibility.h
*
* Definitions controlling symbol naming and visibility.
*
* This file is normally included automatically by the build system.
*/
#ifndef __SYSTEMLIB_VISIBILITY_H
#define __SYSTEMLIB_VISIBILITY_H
#ifdef __EXPORT
# undef __EXPORT
#endif
#define __EXPORT __attribute__ ((visibility ("default")))
#ifdef __PRIVATE
# undef __PRIVATE
#endif
#define __PRIVATE __attribute__ ((visibility ("hidden")))
#ifdef __cplusplus
# define __BEGIN_DECLS extern "C" {
# define __END_DECLS }
#else
# define __BEGIN_DECLS
# define __END_DECLS
#endif
#endif

0
apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp → src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp

0
apps/attitude_estimator_ekf/attitude_estimator_ekf_params.c → src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c

0
apps/attitude_estimator_ekf/attitude_estimator_ekf_params.h → src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter.c → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter.c

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter.h → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter.h

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.c → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.c

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.h → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_initialize.h

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.c → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.c

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.h → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_terminate.h

0
apps/attitude_estimator_ekf/codegen/attitudeKalmanfilter_types.h → src/modules/attitude_estimator_ekf/codegen/attitudeKalmanfilter_types.h

0
apps/attitude_estimator_ekf/codegen/cross.c → src/modules/attitude_estimator_ekf/codegen/cross.c

0
apps/attitude_estimator_ekf/codegen/cross.h → src/modules/attitude_estimator_ekf/codegen/cross.h

0
apps/attitude_estimator_ekf/codegen/eye.c → src/modules/attitude_estimator_ekf/codegen/eye.c

0
apps/attitude_estimator_ekf/codegen/eye.h → src/modules/attitude_estimator_ekf/codegen/eye.h

0
apps/attitude_estimator_ekf/codegen/mrdivide.c → src/modules/attitude_estimator_ekf/codegen/mrdivide.c

0
apps/attitude_estimator_ekf/codegen/mrdivide.h → src/modules/attitude_estimator_ekf/codegen/mrdivide.h

0
apps/attitude_estimator_ekf/codegen/norm.c → src/modules/attitude_estimator_ekf/codegen/norm.c

0
apps/attitude_estimator_ekf/codegen/norm.h → src/modules/attitude_estimator_ekf/codegen/norm.h

0
apps/attitude_estimator_ekf/codegen/rdivide.c → src/modules/attitude_estimator_ekf/codegen/rdivide.c

0
apps/attitude_estimator_ekf/codegen/rdivide.h → src/modules/attitude_estimator_ekf/codegen/rdivide.h

0
apps/attitude_estimator_ekf/codegen/rtGetInf.c → src/modules/attitude_estimator_ekf/codegen/rtGetInf.c

0
apps/attitude_estimator_ekf/codegen/rtGetInf.h → src/modules/attitude_estimator_ekf/codegen/rtGetInf.h

0
apps/attitude_estimator_ekf/codegen/rtGetNaN.c → src/modules/attitude_estimator_ekf/codegen/rtGetNaN.c

0
apps/attitude_estimator_ekf/codegen/rtGetNaN.h → src/modules/attitude_estimator_ekf/codegen/rtGetNaN.h

0
apps/attitude_estimator_ekf/codegen/rt_defines.h → src/modules/attitude_estimator_ekf/codegen/rt_defines.h

0
apps/attitude_estimator_ekf/codegen/rt_nonfinite.c → src/modules/attitude_estimator_ekf/codegen/rt_nonfinite.c

0
apps/attitude_estimator_ekf/codegen/rt_nonfinite.h → src/modules/attitude_estimator_ekf/codegen/rt_nonfinite.h

0
apps/attitude_estimator_ekf/codegen/rtwtypes.h → src/modules/attitude_estimator_ekf/codegen/rtwtypes.h

16
src/modules/attitude_estimator_ekf/module.mk

@ -0,0 +1,16 @@ @@ -0,0 +1,16 @@
MODULE_NAME = attitude_estimator_ekf
SRCS = attitude_estimator_ekf_main.cpp \
attitude_estimator_ekf_params.c \
codegen/attitudeKalmanfilter_initialize.c \
codegen/attitudeKalmanfilter_terminate.c \
codegen/attitudeKalmanfilter.c \
codegen/cross.c \
codegen/eye.c \
codegen/mrdivide.c \
codegen/norm.c \
codegen/rdivide.c \
codegen/rt_nonfinite.c \
codegen/rtGetInf.c \
codegen/rtGetNaN.c

0
apps/commander/calibration_routines.c → src/modules/commander/calibration_routines.c

0
apps/commander/calibration_routines.h → src/modules/commander/calibration_routines.h

0
apps/commander/commander.c → src/modules/commander/commander.c

0
apps/commander/commander.h → src/modules/commander/commander.h

13
apps/ardrone_interface/Makefile → src/modules/commander/module.mk

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -32,11 +32,10 @@ @@ -32,11 +32,10 @@
############################################################################
#
# Makefile to build ardrone interface
# Main system state machine
#
APPNAME = ardrone_interface
PRIORITY = SCHED_PRIORITY_MAX - 15
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MODULE_COMMAND = commander
SRCS = commander.c \
state_machine_helper.c \
calibration_routines.c

0
apps/commander/state_machine_helper.c → src/modules/commander/state_machine_helper.c

0
apps/commander/state_machine_helper.h → src/modules/commander/state_machine_helper.h

0
apps/systemcmds/eeprom/24xxxx_mtd.c → src/systemcmds/eeprom/24xxxx_mtd.c

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save