Adding config changes to allow PX4 to be built for the Excelsior board.

This commit is contained in:
jwilson 2016-05-02 14:53:24 -07:00 committed by Julian Oes
parent 0c5c111cdd
commit c87a8bedb6
7 changed files with 20 additions and 63 deletions

View File

@ -199,6 +199,12 @@ qurt_eagle_legacy_driver_default:
posix_eagle_legacy_driver_default:
$(call cmake-build,$@)
qurt_excelsior_default:
$(call cmake-build,$@)
posix_excelsior_default:
$(call cmake-build,$@)
excelsior_default: posix_excelsior_default qurt_excelsior_default
posix_rpi2_default:
$(call cmake-build,$@)

View File

@ -1,65 +1,7 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon")
set(config_generate_parameters_scope ALL)
set(CONFIG_SHMEM "1")
include(configs/posix_sdflight_default)
# This definition allows to differentiate if this just the usual POSIX build
# or if it is for the Snapdragon.
add_definitions(
-D__PX4_POSIX_EAGLE
)
set(config_module_list
drivers/device
drivers/blinkm
drivers/pwm_out_sim
drivers/rgbled
drivers/led
drivers/boards/sitl
drivers/qshell/posix
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/topic_listener
modules/mavlink
modules/attitude_estimator_ekf
modules/ekf_att_pos_estimator
modules/mc_pos_control
modules/mc_att_control
modules/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/muorb/krait
modules/sensors
modules/dataman
modules/sdlog2
modules/simulator
modules/commander
lib/controllib
lib/mathlib
lib/mathlib/math/filter
lib/conversion
lib/ecl
lib/geo
lib/geo_lookup
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
lib/DriverFramework/framework
platforms/common
platforms/posix/px4_layer
platforms/posix/work_queue
)

View File

@ -197,7 +197,7 @@ else()
endif()
if ("${BOARD}" STREQUAL "eagle")
if ("${BOARD}" STREQUAL "eagle" OR "${BOARD}" STREQUAL "excelsior")
if ("$ENV{HEXAGON_ARM_SYSROOT}" STREQUAL "")
message(FATAL_ERROR "HEXAGON_ARM_SYSROOT not set")

View File

@ -4,7 +4,7 @@ px4_posix_generate_builtin_commands(
OUT apps.h
MODULE_LIST ${module_libraries})
if ("${BOARD}" STREQUAL "eagle")
if ("${BOARD}" STREQUAL "eagle" OR ("${BOARD}" STREQUAL "excelsior"))
include(fastrpc)
include(linux_app)

View File

@ -75,6 +75,11 @@
#define HW_ARCH "LINUXTEST"
#endif
#ifdef CONFIG_ARCH_BOARD_EXCELSIOR
#define HW_ARCH "LINUXTEST"
#endif
#ifdef CONFIG_ARCH_BOARD_RPI2
#define HW_ARCH "LINUXTEST"
#endif

View File

@ -166,7 +166,7 @@ hrt_abstime _hrt_absolute_time_internal(void)
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts) + dsp_offset;
#elif defined(__PX4_POSIX_EAGLE)
#elif (defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_EXCELSIOR))
// Don't do any offseting on the Linux side on the Snapdragon.
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts);

View File

@ -31,7 +31,7 @@
*
****************************************************************************/
#define MAX_SHMEM_PARAMS 3850 //MAP_SIZE - (LOCK_SIZE - sizeof(struct shmem_info))
#define MAX_SHMEM_PARAMS 2000 //MAP_SIZE - (LOCK_SIZE - sizeof(struct shmem_info))
struct shmem_info {
union param_value_u params_val[MAX_SHMEM_PARAMS];
@ -44,7 +44,11 @@ struct shmem_info {
} __attribute__((packed));
#endif
#if (defined(__PX4_POSIX_EXCELSIOR) || defined(__PX4_QURT_EXCELSIOR))
#define MAP_ADDRESS 0x861FC000
#else
#define MAP_ADDRESS 0xfbfc000
#endif
#define MAP_SIZE 16384
#define MAP_MASK (MAP_SIZE - 1)