Daniel Agar
6 years ago
committed by
David Sidrane
515 changed files with 10738 additions and 11752 deletions
@ -0,0 +1,86 @@
@@ -0,0 +1,86 @@
|
||||
|
||||
px4_add_board( |
||||
VENDOR aerotenna |
||||
MODEL ocpoc |
||||
LABEL ubuntu |
||||
PLATFORM posix |
||||
ARCH cortex-a9 |
||||
TOOLCHAIN Toolchain-arm-linux-gnueabihf |
||||
TESTING |
||||
|
||||
DRIVERS |
||||
#barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
linux_pwm_out |
||||
linux_sbus |
||||
#imu # all available imu drivers |
||||
#magnetometer # all available magnetometer drivers |
||||
ocpoc_adc |
||||
rgbled |
||||
pwm_out_sim |
||||
#telemetry # all available telemetry drivers |
||||
vmount |
||||
|
||||
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers |
||||
mpu9250 |
||||
ms5611 |
||||
hmc5883 |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
#simulator |
||||
#uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
esc_calib |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
#hwtest # Hardware test |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
) |
@ -0,0 +1,116 @@
@@ -0,0 +1,116 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR airmind |
||||
MODEL mindpx-v2 |
||||
ARCH cortex-m4 |
||||
ROMFS |
||||
ROMFSROOT px4fmu_common |
||||
TESTING |
||||
UAVCAN_INTERFACES 1 |
||||
|
||||
SERIAL_PORTS |
||||
GPS1:/dev/ttyS3 |
||||
TEL1:/dev/ttyS1 |
||||
TEL2:/dev/ttyS2 |
||||
|
||||
DRIVERS |
||||
barometer # all available barometer drivers |
||||
batt_smbus |
||||
blinkm |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#heater |
||||
#imu # all available imu drivers |
||||
imu/l3gd20 |
||||
imu/lsm303d |
||||
imu/mpu6000 |
||||
imu/mpu9250 |
||||
irlock |
||||
magnetometer # all available magnetometer drivers |
||||
mkblctrl |
||||
oreoled |
||||
pca9685 |
||||
pwm_input |
||||
pwm_out_sim |
||||
px4flow |
||||
px4fmu |
||||
rc_input |
||||
rgbled |
||||
stm32 |
||||
stm32/adc |
||||
stm32/tone_alarm |
||||
tap_esc |
||||
telemetry # all available telemetry drivers |
||||
test_ppm |
||||
vmount |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dumpfile |
||||
esc_calib |
||||
hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
usb_connected |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
hwtest # Hardware test |
||||
#matlab_csv_serial |
||||
#publisher |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
#subscriber |
||||
uuv_example_app |
||||
|
||||
) |
@ -1,5 +1,5 @@
@@ -1,5 +1,5 @@
|
||||
/**************************************************************************** |
||||
* nuttx-configs/px4fmu-v3/scripts/ld.script |
||||
* scripts/ld.script |
||||
* |
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
@ -0,0 +1,115 @@
@@ -0,0 +1,115 @@
|
||||
|
||||
# The Eagle board is the first generation Snapdragon Flight board by Qualcomm. |
||||
|
||||
include(px4_git) |
||||
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
list(APPEND CMAKE_MODULE_PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
|
||||
# Get $QC_SOC_TARGET from environment if existing. |
||||
if (DEFINED ENV{QC_SOC_TARGET}) |
||||
set(QC_SOC_TARGET $ENV{QC_SOC_TARGET}) |
||||
else() |
||||
set(QC_SOC_TARGET "APQ8074") |
||||
endif() |
||||
|
||||
# Disable the creation of the parameters.xml file by scanning individual |
||||
# source files, and scan all source files. This will create a parameters.xml |
||||
# file that contains all possible parameters, even if the associated module |
||||
# is not used. This is necessary for parameter synchronization between the |
||||
# ARM and DSP processors. |
||||
set(DISABLE_PARAMS_MODULE_SCOPING TRUE) |
||||
|
||||
set(CONFIG_SHMEM "1") |
||||
add_definitions(-DORB_COMMUNICATOR) |
||||
|
||||
# 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) |
||||
|
||||
px4_add_board( |
||||
PLATFORM posix |
||||
VENDOR atlflight |
||||
MODEL eagle |
||||
LABEL default |
||||
TESTING |
||||
TOOLCHAIN |
||||
toolchain/Toolchain-arm-linux-gnueabihf |
||||
|
||||
DRIVERS |
||||
#barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
linux_sbus |
||||
#imu # all available imu drivers |
||||
#magnetometer # all available magnetometer drivers |
||||
rgbled |
||||
pwm_out_sim |
||||
qshell/posix |
||||
#telemetry # all available telemetry drivers |
||||
vmount |
||||
|
||||
MODULES |
||||
muorb/krait |
||||
|
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
simulator |
||||
#uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
#bl_update |
||||
#config |
||||
#dumpfile |
||||
esc_calib |
||||
#hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
#mtd |
||||
#nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
#hwtest # Hardware test |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
) |
@ -0,0 +1,83 @@
@@ -0,0 +1,83 @@
|
||||
|
||||
# The Eagle board is the first generation Snapdragon Flight board by Qualcomm. |
||||
# |
||||
# This cmake config builds for QURT which is the operating system running on |
||||
# the DSP side. |
||||
|
||||
# Get $QC_SOC_TARGET from environment if existing. |
||||
if (DEFINED ENV{QC_SOC_TARGET}) |
||||
set(QC_SOC_TARGET $ENV{QC_SOC_TARGET}) |
||||
else() |
||||
set(QC_SOC_TARGET "APQ8074") |
||||
endif() |
||||
|
||||
include(px4_git) |
||||
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
list(APPEND CMAKE_MODULE_PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
|
||||
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "") |
||||
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set") |
||||
else() |
||||
set(HEXAGON_SDK_ROOT $ENV{HEXAGON_SDK_ROOT}) |
||||
endif() |
||||
|
||||
include(toolchain/Toolchain-qurt) |
||||
include(qurt_flags) |
||||
include_directories(${HEXAGON_SDK_INCLUDES}) |
||||
|
||||
set(CONFIG_SHMEM "1") |
||||
add_definitions(-DORB_COMMUNICATOR) |
||||
|
||||
# Disable the creation of the parameters.xml file by scanning individual |
||||
# source files, and scan all source files. This will create a parameters.xml |
||||
# file that contains all possible parameters, even if the associated module |
||||
# is not used. This is necessary for parameter synchronization between the |
||||
# ARM and DSP processors. |
||||
set(DISABLE_PARAMS_MODULE_SCOPING TRUE) |
||||
|
||||
# This definition allows to differentiate the specific board. |
||||
add_definitions(-D__PX4_QURT_EAGLE) |
||||
|
||||
px4_add_board( |
||||
PLATFORM qurt |
||||
VENDOR atlflight |
||||
MODEL eagle |
||||
LABEL qurt-default |
||||
|
||||
DRIVERS |
||||
gps |
||||
spektrum_rc |
||||
qshell/qurt |
||||
snapdragon_pwm_out |
||||
|
||||
DF_DRIVERS |
||||
mpu9250 |
||||
bmp280 |
||||
hmc5883 |
||||
trone |
||||
isl29501 |
||||
ltc2946 |
||||
|
||||
MODULES |
||||
muorb/adsp |
||||
|
||||
attitude_estimator_q |
||||
commander |
||||
ekf2 |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
land_detector |
||||
landing_target_estimator |
||||
local_position_estimator |
||||
mc_att_control |
||||
mc_pos_control |
||||
position_estimator_inav |
||||
sensors |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
param |
||||
) |
@ -0,0 +1,115 @@
@@ -0,0 +1,115 @@
|
||||
|
||||
# Excelsior is the code name of a board currently in development. |
||||
|
||||
include(px4_git) |
||||
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
list(APPEND CMAKE_MODULE_PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
|
||||
# Get $QC_SOC_TARGET from environment if existing. |
||||
if (DEFINED ENV{QC_SOC_TARGET}) |
||||
set(QC_SOC_TARGET $ENV{QC_SOC_TARGET}) |
||||
else() |
||||
set(QC_SOC_TARGET "APQ8074") |
||||
endif() |
||||
|
||||
# Disable the creation of the parameters.xml file by scanning individual |
||||
# source files, and scan all source files. This will create a parameters.xml |
||||
# file that contains all possible parameters, even if the associated module |
||||
# is not used. This is necessary for parameter synchronization between the |
||||
# ARM and DSP processors. |
||||
set(DISABLE_PARAMS_MODULE_SCOPING TRUE) |
||||
|
||||
set(CONFIG_SHMEM "1") |
||||
add_definitions(-DORB_COMMUNICATOR) |
||||
|
||||
# This definition allows to differentiate if this just the usual POSIX build |
||||
# or if it is for the Snapdragon. |
||||
add_definitions(-D__PX4_POSIX_EXCELSIOR) |
||||
|
||||
px4_add_board( |
||||
PLATFORM posix |
||||
VENDOR atlflight |
||||
MODEL excelsior |
||||
LABEL default |
||||
TESTING |
||||
TOOLCHAIN |
||||
toolchain/Toolchain-arm-oemllib32-linux-gnueabi |
||||
|
||||
DRIVERS |
||||
#barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
linux_sbus |
||||
#imu # all available imu drivers |
||||
#magnetometer # all available magnetometer drivers |
||||
rgbled |
||||
pwm_out_sim |
||||
qshell/posix |
||||
#telemetry # all available telemetry drivers |
||||
vmount |
||||
|
||||
MODULES |
||||
muorb/krait |
||||
|
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
simulator |
||||
#uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
#bl_update |
||||
#config |
||||
#dumpfile |
||||
esc_calib |
||||
#hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
#mtd |
||||
#nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
#hwtest # Hardware test |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
) |
@ -0,0 +1,82 @@
@@ -0,0 +1,82 @@
|
||||
# Excelsior is the code name of a board currently in development. |
||||
# |
||||
# This cmake config builds for QURT which is the operating system running on |
||||
# the DSP side. |
||||
|
||||
# Get $QC_SOC_TARGET from environment if existing. |
||||
if (DEFINED ENV{QC_SOC_TARGET}) |
||||
set(QC_SOC_TARGET $ENV{QC_SOC_TARGET}) |
||||
else() |
||||
set(QC_SOC_TARGET "APQ8074") |
||||
endif() |
||||
|
||||
include(px4_git) |
||||
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
list(APPEND CMAKE_MODULE_PATH "${PX4_SOURCE_DIR}/boards/atlflight/cmake_hexagon") |
||||
|
||||
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "") |
||||
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set") |
||||
else() |
||||
set(HEXAGON_SDK_ROOT $ENV{HEXAGON_SDK_ROOT}) |
||||
endif() |
||||
|
||||
include(toolchain/Toolchain-qurt) |
||||
include(qurt_flags) |
||||
include_directories(${HEXAGON_SDK_INCLUDES}) |
||||
|
||||
set(CONFIG_SHMEM "1") |
||||
add_definitions(-DORB_COMMUNICATOR) |
||||
|
||||
# Disable the creation of the parameters.xml file by scanning individual |
||||
# source files, and scan all source files. This will create a parameters.xml |
||||
# file that contains all possible parameters, even if the associated module |
||||
# is not used. This is necessary for parameter synchronization between the |
||||
# ARM and DSP processors. |
||||
set(DISABLE_PARAMS_MODULE_SCOPING TRUE) |
||||
|
||||
# This definition allows to differentiate the specific board. |
||||
add_definitions(-D__PX4_QURT_EXCELSIOR) |
||||
|
||||
px4_add_board( |
||||
PLATFORM qurt |
||||
VENDOR atlflight |
||||
MODEL excelsior |
||||
LABEL qurt-default |
||||
|
||||
DRIVERS |
||||
gps |
||||
spektrum_rc |
||||
qshell/qurt |
||||
snapdragon_pwm_out |
||||
|
||||
DF_DRIVERS |
||||
mpu9250 |
||||
bmp280 |
||||
hmc5883 |
||||
trone |
||||
isl29501 |
||||
ltc2946 |
||||
|
||||
MODULES |
||||
muorb/adsp |
||||
|
||||
attitude_estimator_q |
||||
commander |
||||
ekf2 |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
land_detector |
||||
landing_target_estimator |
||||
local_position_estimator |
||||
mc_att_control |
||||
mc_pos_control |
||||
position_estimator_inav |
||||
sensors |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
param |
||||
) |
@ -0,0 +1,116 @@
@@ -0,0 +1,116 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR atmel |
||||
MODEL same70xplained |
||||
ARCH cortex-m7 |
||||
ROMFS |
||||
ROMFSROOT px4fmu_common |
||||
TESTING |
||||
#UAVCAN_INTERFACES 1 |
||||
|
||||
SERIAL_PORTS |
||||
GPS1:/dev/ttyS3 |
||||
TEL1:/dev/ttyS1 |
||||
TEL2:/dev/ttyS2 |
||||
|
||||
DRIVERS |
||||
barometer # all available barometer drivers |
||||
batt_smbus |
||||
blinkm |
||||
#camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#heater |
||||
#imu # all available imu drivers |
||||
imu/mpu6000 |
||||
imu/mpu9250 |
||||
imu/lsm303d |
||||
imu/l3gd20 |
||||
irlock |
||||
magnetometer # all available magnetometer drivers |
||||
mkblctrl |
||||
oreoled |
||||
pca9685 |
||||
#pwm_input |
||||
pwm_out_sim |
||||
px4flow |
||||
px4fmu |
||||
#rc_input |
||||
rgbled |
||||
samv7 |
||||
#WIP samv7/adc |
||||
samv7/tone_alarm |
||||
tap_esc |
||||
telemetry # all available telemetry drivers |
||||
#test_ppm |
||||
vmount |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
#WIP uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dumpfile |
||||
esc_calib |
||||
#WIP hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
#mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
#usb_connected |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
hwtest # Hardware test |
||||
#matlab_csv_serial |
||||
#publisher |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
#subscriber |
||||
uuv_example_app |
||||
|
||||
) |
@ -0,0 +1,122 @@
@@ -0,0 +1,122 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR auav |
||||
MODEL x21 |
||||
LABEL default |
||||
ARCH cortex-m4 |
||||
ROMFS |
||||
ROMFSROOT px4fmu_common |
||||
IO px4io-v2_default |
||||
TESTING |
||||
UAVCAN_INTERFACES 1 |
||||
|
||||
SERIAL_PORTS |
||||
GPS1:/dev/ttyS3 |
||||
TEL1:/dev/ttyS1 |
||||
TEL2:/dev/ttyS2 |
||||
|
||||
DRIVERS |
||||
barometer # all available barometer drivers |
||||
batt_smbus |
||||
blinkm |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#heater |
||||
#imu # all available imu drivers |
||||
imu/mpu6000 |
||||
imu/mpu9250 |
||||
irlock |
||||
magnetometer # all available magnetometer drivers |
||||
#md25 |
||||
mkblctrl |
||||
oreoled |
||||
pca8574 |
||||
pca9685 |
||||
#pmw3901 |
||||
protocol_splitter |
||||
pwm_input |
||||
pwm_out_sim |
||||
px4flow |
||||
px4fmu |
||||
px4io |
||||
rgbled |
||||
#rgbled_pwm |
||||
roboclaw |
||||
stm32 |
||||
stm32/adc |
||||
stm32/tone_alarm |
||||
tap_esc |
||||
telemetry # all available telemetry drivers |
||||
test_ppm |
||||
vmount |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dumpfile |
||||
esc_calib |
||||
hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
usb_connected |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
hwtest # Hardware test |
||||
#matlab_csv_serial |
||||
#publisher |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
#subscriber |
||||
uuv_example_app |
||||
|
||||
) |
@ -0,0 +1,121 @@
@@ -0,0 +1,121 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR av |
||||
MODEL x-v1 |
||||
ARCH cortex-m7 |
||||
ROMFS |
||||
ROMFSROOT px4fmu_common |
||||
TESTING |
||||
UAVCAN_INTERFACES 2 |
||||
|
||||
SERIAL_PORTS |
||||
GPS1:/dev/ttyS6 |
||||
TEL1:/dev/ttyS0 |
||||
TEL2:/dev/ttyS1 |
||||
TEL3:/dev/ttyS2 |
||||
TEL4:/dev/ttyS3 |
||||
|
||||
DRIVERS |
||||
barometer # all available barometer drivers |
||||
batt_smbus |
||||
blinkm |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#heater |
||||
#imu # all available imu drivers |
||||
imu/adis16477 |
||||
irlock |
||||
magnetometer # all available magnetometer drivers |
||||
#md25 |
||||
mkblctrl |
||||
#oreoled |
||||
#pca8574 |
||||
pca9685 |
||||
#pmw3901 |
||||
protocol_splitter |
||||
#pwm_input |
||||
pwm_out_sim |
||||
px4flow |
||||
px4fmu |
||||
rc_input |
||||
#rgbled |
||||
#rgbled_pwm |
||||
roboclaw |
||||
stm32 |
||||
stm32/adc |
||||
#stm32/tone_alarm |
||||
tap_esc |
||||
telemetry # all available telemetry drivers |
||||
test_ppm |
||||
vmount |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dumpfile |
||||
esc_calib |
||||
hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
#usb_connected |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
hwtest # Hardware test |
||||
#matlab_csv_serial |
||||
#publisher |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
#subscriber |
||||
uuv_example_app |
||||
|
||||
) |
@ -1,5 +1,5 @@
@@ -1,5 +1,5 @@
|
||||
/**************************************************************************** |
||||
* nuttx-configs/av-x/scripts/script.ld |
||||
* scripts/script.ld |
||||
* |
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
@ -0,0 +1,84 @@
@@ -0,0 +1,84 @@
|
||||
|
||||
px4_add_board( |
||||
VENDOR beaglebone |
||||
MODEL blue |
||||
LABEL cross |
||||
PLATFORM posix |
||||
ARCH cortex-a8 |
||||
TOOLCHAIN Toolchain-arm-linux-gnueabihf |
||||
TESTING |
||||
|
||||
DRIVERS |
||||
#barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#imu # all available imu drivers |
||||
#magnetometer # all available magnetometer drivers |
||||
pwm_out_sim |
||||
#telemetry # all available telemetry drivers |
||||
vmount |
||||
|
||||
linux_gpio |
||||
linux_pwm_out |
||||
linux_sbus |
||||
bbblue_adc |
||||
|
||||
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers |
||||
mpu9250 |
||||
bmp280 |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
#uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
esc_calib |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
sd_bench |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
#hwtest # Hardware test |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
) |
@ -0,0 +1,83 @@
@@ -0,0 +1,83 @@
|
||||
|
||||
px4_add_board( |
||||
VENDOR beaglebone |
||||
MODEL blue |
||||
LABEL native |
||||
PLATFORM posix |
||||
TOOLCHAIN Toolchain-native |
||||
TESTING |
||||
|
||||
DRIVERS |
||||
#barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
gps |
||||
#imu # all available imu drivers |
||||
#magnetometer # all available magnetometer drivers |
||||
pwm_out_sim |
||||
#telemetry # all available telemetry drivers |
||||
vmount |
||||
|
||||
linux_gpio |
||||
linux_pwm_out |
||||
linux_sbus |
||||
bbblue_adc |
||||
|
||||
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers |
||||
mpu9250 |
||||
bmp280 |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
gnd_att_control |
||||
gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
#uavcan |
||||
vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
esc_calib |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
sd_bench |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
ver |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
#hwtest # Hardware test |
||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values |
||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app |
||||
rover_steering_control # Rover example app |
||||
segway |
||||
) |
@ -0,0 +1,73 @@
@@ -0,0 +1,73 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR bitcraze |
||||
MODEL crazyflie |
||||
ARCH cortex-m4 |
||||
ROMFS |
||||
ROMFSROOT px4fmu_common |
||||
|
||||
DRIVERS |
||||
barometer/lps25h |
||||
distance_sensor/vl53lxx |
||||
gps |
||||
imu/mpu9250 |
||||
pmw3901 |
||||
px4fmu |
||||
stm32 |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
#fw_att_control |
||||
#fw_pos_control_l1 |
||||
#gnd_att_control |
||||
#gnd_pos_control |
||||
#gpio_led |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
position_estimator_inav |
||||
sensors |
||||
syslink |
||||
#uavcan |
||||
#vtol_att_control |
||||
wind_estimator |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dumpfile |
||||
esc_calib |
||||
hardfault_log |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
#tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
usb_connected |
||||
ver |
||||
|
||||
) |
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue