Merged with upstream export-build branch

This commit is contained in:
Lorenz Meier 2013-04-27 13:26:25 +02:00
commit 852e6e2f49
72 changed files with 41 additions and 43 deletions

View File

@ -15,6 +15,8 @@ MODULES += drivers/boards/px4fmu
MODULES += drivers/lsm303d
MODULES += drivers/l3gd20
MODULES += drivers/ardrone_interface
MODULES += drivers/px4io
MODULES += modules/sensors
#
# System commands
@ -43,6 +45,12 @@ MODULES += modules/mavlink_onboard
# Estimation modules (EKF / other filters)
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/position_estimator_mc
#
# Logging
#
MODULES += modules/sdlog
#
# Transitional support - add commands from the NuttX export archive.
@ -74,10 +82,6 @@ BUILTIN_COMMANDS := \
$(call _B, ms5611, , 2048, ms5611_main ) \
$(call _B, multirotor_att_control, SCHED_PRIORITY_MAX-15, 2048, multirotor_att_control_main) \
$(call _B, multirotor_pos_control, SCHED_PRIORITY_MAX-25, 2048, multirotor_pos_control_main) \
$(call _B, position_estimator, , 4096, position_estimator_main ) \
$(call _B, px4io, , 2048, px4io_main ) \
$(call _B, sdlog, SCHED_PRIORITY_MAX-30, 2048, sdlog_main ) \
$(call _B, sensors, SCHED_PRIORITY_MAX-5, 4096, sensors_main ) \
$(call _B, sercon, , 2048, sercon_main ) \
$(call _B, serdis, , 2048, serdis_main ) \
$(call _B, tone_alarm, , 2048, tone_alarm_main ) \

View File

@ -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,7 +32,8 @@
****************************************************************************/
/**
* @file Driver for the ST L3GD20 MEMS gyro connected via SPI.
* @file l3gd20.cpp
* Driver for the ST L3GD20 MEMS gyro connected via SPI.
*/
#include <nuttx/config.h>

View File

@ -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
@ -35,8 +35,7 @@
# Interface driver for the PX4IO board.
#
APPNAME = px4io
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
MODULE_COMMAND = px4io
include $(APPDIR)/mk/app.mk
SRCS = px4io.cpp \
uploader.cpp

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012,2013 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

View File

@ -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,7 +32,8 @@
****************************************************************************/
/**
* @file Firmware uploader for PX4IO
* @file uploader.cpp
* Firmware uploader for PX4IO
*/
#include <nuttx/config.h>

View File

@ -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,7 +32,8 @@
****************************************************************************/
/**
* @file Firmware uploader for PX4IO
* @file uploader.h
* Firmware uploader definitions for PX4IO.
*/
#ifndef _PX4IO_UPLOADER_H

View File

@ -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>

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012-2013 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
@ -35,10 +35,10 @@
# Attitude estimator (Extended Kalman Filter)
#
MODULE_NAME = attitude_estimator_ekf
CXXSRCS = attitude_estimator_ekf_main.cpp
MODULE_COMMAND = attitude_estimator_ekf
SRCS = attitude_estimator_ekf_params.c \
SRCS = attitude_estimator_ekf_main.cpp \
attitude_estimator_ekf_params.c \
codegen/eye.c \
codegen/attitudeKalmanfilter.c \
codegen/mrdivide.c \

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012-2013 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

View File

@ -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
@ -35,11 +35,9 @@
# Makefile to build the position estimator
#
APPNAME = position_estimator_mc
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
MODULE_COMMAND = position_estimator_mc
CSRCS = position_estimator_mc_main.c \
SRCS = position_estimator_mc_main.c \
position_estimator_mc_params.c \
codegen/positionKalmanFilter1D_initialize.c \
codegen/positionKalmanFilter1D_terminate.c \
@ -60,5 +58,3 @@ CSRCS = position_estimator_mc_main.c \
codegen/kalman_dlqe3_terminate.c \
codegen/kalman_dlqe3_data.c \
codegen/randn.c
include $(APPDIR)/mk/app.mk

View File

@ -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
@ -35,9 +35,9 @@
# sdlog Application
#
APPNAME = sdlog
MODULE_COMMAND = sdlog
# The main thread only buffers to RAM, needs a high priority
PRIORITY = SCHED_PRIORITY_MAX - 30
STACKSIZE = 2048
MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
include $(APPDIR)/mk/app.mk
SRCS = sdlog.c \
sdlog_ringbuffer.c

View File

View File

@ -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
@ -35,11 +35,8 @@
# Makefile to build the sensor data collector
#
APPNAME = sensors
PRIORITY = SCHED_PRIORITY_MAX-5
STACKSIZE = 4096
MODULE_COMMAND = sensors
MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
CXXSRCS = sensors.cpp
CSRCS = sensor_params.c
include $(APPDIR)/mk/app.mk
SRCS = sensors.cpp \
sensor_params.c