forked from Archive/PX4-Autopilot
Cut over attitude estimator to new-style config for all boards
This commit is contained in:
parent
c52278f679
commit
3ecdca41e5
|
@ -1,56 +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
|
||||
|
||||
CSRCS = attitude_estimator_ekf_main.c \
|
||||
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
|
|
@ -16,6 +16,11 @@ MODULES += drivers/lsm303d
|
|||
MODULES += drivers/l3gd20
|
||||
MODULES += systemcmds/eeprom
|
||||
|
||||
#
|
||||
# Estimation modules (EKF / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
|
@ -32,7 +37,6 @@ endef
|
|||
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 ) \
|
||||
|
|
|
@ -17,6 +17,11 @@ MODULES += drivers/px4fmu
|
|||
MODULES += drivers/rgbled
|
||||
MODULES += systemcmds/ramtron
|
||||
|
||||
#
|
||||
# Estimation modules (EKF / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
|
@ -32,7 +37,6 @@ endef
|
|||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, adc, , 2048, adc_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, boardinfo, , 2048, boardinfo_main ) \
|
||||
|
|
|
@ -46,7 +46,6 @@
|
|||
#include <stdbool.h>
|
||||
#include <poll.h>
|
||||
#include <fcntl.h>
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <float.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
|
@ -0,0 +1,16 @@
|
|||
|
||||
MODULE_NAME = attitude_estimator_ekf
|
||||
SRCS = attitude_estimator_ekf_main.c \
|
||||
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
|
||||
|
Loading…
Reference in New Issue