Add new posix_eagle_default and qurt_eagle_default targets

This commit is contained in:
Lorenz Meier 2016-01-02 09:30:51 +01:00
parent 55ce8c0c42
commit 2d72c95eda
3 changed files with 151 additions and 0 deletions

View File

@ -166,6 +166,12 @@ qurt_eagle_release:
posix_eagle_release:
$(call cmake-build,$@)
qurt_eagle_default:
$(call cmake-build,$@)
posix_eagle_default:
$(call cmake-build,$@)
posix: posix_sitl_default
sitl_deprecation:

View File

@ -0,0 +1,90 @@
include(qurt/px4_impl_qurt)
if ("${HEXAGON_DRIVERS_ROOT}" STREQUAL "")
message(FATAL_ERROR "HEXAGON_DRIVERS_ROOT is not set")
endif()
if ("${EAGLE_DRIVERS_SRC}" STREQUAL "")
message(FATAL_ERROR "EAGLE_DRIVERS_SRC is not set")
endif()
include_directories(${HEXAGON_DRIVERS_ROOT}/inc)
# For Actual flight we need to link against the driver dynamic libraries
set(target_libraries
-L${HEXAGON_DRIVERS_ROOT}/libs
# The plan is to replace these with our drivers
# mpu9x50
# uart_esc
# csr_gps
# rc_receiver
)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(config_module_list
#
# Board support modules
#
drivers/device
modules/sensors
# The plan is to replace these with our drivers
# $(EAGLE_DRIVERS_SRC)/mpu9x50
# $(EAGLE_DRIVERS_SRC)/uart_esc
# $(EAGLE_DRIVERS_SRC)/rc_receiver
# $(EAGLE_DRIVERS_SRC)/csr_gps
#
# System commands
#
systemcmds/param
#
# Estimation modules (EKF/ SO3 / other filters)
#
#modules/attitude_estimator_ekf
modules/ekf_att_pos_estimator
modules/attitude_estimator_q
modules/position_estimator_inav
#
# Vehicle Control
#
modules/mc_att_control
modules/mc_pos_control
#
# Library modules
#
modules/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/commander
modules/controllib
#
# Libraries
#
lib/mathlib
lib/mathlib/math/filter
lib/geo
lib/geo_lookup
lib/conversion
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
#
# QuRT port
#
platforms/common
platforms/qurt/px4_layer
platforms/posix/work_queue
#
# sources for muorb over fastrpc
#
modules/muorb/adsp
)

View File

@ -0,0 +1,55 @@
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. 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 commands_default.c
* Commands to run for the "qurt_eagle_default" config
*
* @author Mark Charlebois <charlebm@gmail.com>
*/
const char *get_commands()
{
static const char *commands =
"uorb start\n"
"param set CAL_GYRO0_ID 2293760\n"
"param set CAL_ACC0_ID 1310720\n"
"param set CAL_ACC1_ID 1376256\n"
"param set CAL_MAG0_ID 196608\n"
"commander start\n"
;
return commands;
}