Skip to content

Commit

Permalink
sync ctrlalloc boards and add to CI
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Jan 18, 2021
1 parent e87f3d5 commit b18c6ab
Show file tree
Hide file tree
Showing 6 changed files with 54 additions and 16 deletions.
7 changes: 5 additions & 2 deletions .ci/Jenkinsfile-compile
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ pipeline {
"mro_x21-777_default",
"mro_x21_default",
"nxp_fmuk66-v3_default",
"nxp_fmuk66-v3_socketcan",
"nxp_fmuk66-v3_rtps",
"nxp_fmuk66-v3_socketcan",
"nxp_fmurt1062-v1_default",
"nxp_ucans32k146_default",
"omnibus_f4sd_default",
Expand All @@ -68,13 +68,16 @@ pipeline {
"px4_fmu-v2_multicopter",
"px4_fmu-v2_rover",
"px4_fmu-v2_test",
"px4_fmu-v3_ctrlalloc",
"px4_fmu-v3_default",
"px4_fmu-v4_cannode",
"px4_fmu-v4_ctrlalloc",
"px4_fmu-v4_default",
"px4_fmu-v4_optimized",
"px4_fmu-v4pro_default",
"px4_fmu-v5_default",
"px4_fmu-v5_ctrlalloc",
"px4_fmu-v5_debug",
"px4_fmu-v5_default",
"px4_fmu-v5_fixedwing",
"px4_fmu-v5_multicopter",
"px4_fmu-v5_optimized",
Expand Down
7 changes: 5 additions & 2 deletions .github/workflows/compile_nuttx.yml
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ jobs:
mro_pixracerpro_default,
mro_x21-777_default,
mro_x21_default,
nxp_fmuk66-v3_default,
nxp_fmuk66-e_default,
nxp_fmuk66-v3_socketcan,
nxp_fmuk66-v3_default,
nxp_fmuk66-v3_rtps,
nxp_fmuk66-v3_socketcan,
nxp_fmurt1062-v1_default,
nxp_ucans32k146_default,
omnibus_f4sd_default,
Expand All @@ -48,11 +48,14 @@ jobs:
px4_fmu-v2_multicopter,
px4_fmu-v2_rover,
px4_fmu-v2_test,
px4_fmu-v3_ctrlalloc,
px4_fmu-v3_default,
px4_fmu-v4_cannode,
px4_fmu-v4_ctrlalloc,
px4_fmu-v4_default,
px4_fmu-v4_optimized,
px4_fmu-v4pro_default,
px4_fmu-v5_ctrlalloc,
px4_fmu-v5_default,
px4_fmu-v5_fixedwing,
px4_fmu-v5_multicopter,
Expand Down
10 changes: 7 additions & 3 deletions boards/px4/fmu-v3/ctrlalloc.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@ px4_add_board(
TEL2:/dev/ttyS2
TEL4:/dev/ttyS6
DRIVERS
adc
adc/board_adc
adc/ads1115
barometer # all available barometer drivers
batt_smbus
camera_capture
Expand All @@ -35,20 +36,20 @@ px4_add_board(
imu/l3gd20
imu/lsm303d
imu/invensense/icm20608g
imu/invensense/icm20948
imu/invensense/mpu6000
imu/invensense/mpu9250
imu/icm20948
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
#lights/rgbled_pwm
magnetometer # all available magnetometer drivers
mkblctrl
#optical_flow # all available optical flow drivers
optical_flow/px4flow
#osd
pca9685
pca9685_pwm_out
#power_monitor/ina226
#protocol_splitter
pwm_input
Expand All @@ -73,6 +74,7 @@ px4_add_board(
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
Expand Down Expand Up @@ -103,6 +105,7 @@ px4_add_board(
hardfault_log
i2cdetect
led_control
mft
mixer
motor_ramp
motor_test
Expand All @@ -114,6 +117,7 @@ px4_add_board(
reboot
reflect
sd_bench
system_time
tests # tests and test runner
top
topic_listener
Expand Down
14 changes: 12 additions & 2 deletions boards/px4/fmu-v4/ctrlalloc.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v4
LABEL default
LABEL ctrlalloc
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m4
ROMFSROOT px4fmu_common
Expand All @@ -13,8 +13,11 @@ px4_add_board(
GPS1:/dev/ttyS3
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
WIFI:/dev/ttyS0

DRIVERS
adc
adc/board_adc
adc/ads1115
barometer # all available barometer drivers
batt_smbus
camera_capture
Expand Down Expand Up @@ -42,6 +45,7 @@ px4_add_board(
optical_flow # all available optical flow drivers
#osd
pca9685
pca9685_pwm_out
#protocol_splitter
pwm_input
pwm_out_sim
Expand All @@ -66,6 +70,7 @@ px4_add_board(
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
Expand Down Expand Up @@ -97,6 +102,7 @@ px4_add_board(
hardfault_log
i2cdetect
led_control
mft
mixer
motor_ramp
motor_test
Expand All @@ -108,6 +114,7 @@ px4_add_board(
reboot
reflect
sd_bench
system_time
tests # tests and test runner
top
topic_listener
Expand All @@ -116,7 +123,10 @@ px4_add_board(
ver
work_queue
EXAMPLES
fake_gyro
fake_magnetometer
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
gyro_fft
hello
hwtest # Hardware test
#matlab_csv_serial
Expand Down
15 changes: 12 additions & 3 deletions boards/px4/fmu-v5/ctrlalloc.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5
LABEL default
LABEL ctrlalloc
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
Expand All @@ -16,7 +16,8 @@ px4_add_board(
TEL2:/dev/ttyS2
TEL4:/dev/ttyS3
DRIVERS
adc
adc/board_adc
adc/ads1115
barometer # all available barometer drivers
batt_smbus
camera_capture
Expand All @@ -30,7 +31,7 @@ px4_add_board(
imu/adis16448
imu/adis16477
imu/adis16497
imu/bmi055
imu/bosch/bmi055
imu/invensense/icm20602
imu/invensense/icm20689
#imu/mpu6000 # legacy icm20602/icm20689 driver
Expand All @@ -44,6 +45,7 @@ px4_add_board(
optical_flow # all available optical flow drivers
#osd
pca9685
pca9685_pwm_out
power_monitor/ina226
#protocol_splitter
pwm_input
Expand Down Expand Up @@ -71,6 +73,7 @@ px4_add_board(
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
Expand All @@ -90,6 +93,7 @@ px4_add_board(
sensors
sih
temperature_compensation
uuv_att_control
vmount
vtol_att_control
SYSTEMCMDS
Expand All @@ -101,6 +105,7 @@ px4_add_board(
hardfault_log
i2cdetect
led_control
mft
mixer
motor_ramp
motor_test
Expand All @@ -112,6 +117,7 @@ px4_add_board(
reboot
reflect
sd_bench
system_time
tests # tests and test runner
top
topic_listener
Expand All @@ -120,7 +126,10 @@ px4_add_board(
ver
work_queue
EXAMPLES
fake_gyro
fake_magnetometer
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
gyro_fft
hello
hwtest # Hardware test
#matlab_csv_serial
Expand Down
17 changes: 13 additions & 4 deletions boards/px4/sitl/ctrlalloc.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,9 @@ px4_add_board(
PLATFORM posix
VENDOR px4
MODEL sitl
LABEL default
ROMFSROOT px4fmu_common
LABEL ctrlalloc
EMBEDDED_METADATA parameters
TESTING
DRIVERS
#barometer # all available barometer drivers
Expand All @@ -15,12 +17,14 @@ px4_add_board(
gps
#imu # all available imu drivers
#magnetometer # all available magnetometer drivers
#protocol_splitter
pwm_out_sim
rpm/rpm_simulator
#telemetry # all available telemetry drivers
tone_alarm
#uavcan
MODULES
airship_att_control
airspeed_selector
angular_velocity_controller
attitude_estimator_q
Expand All @@ -30,18 +34,20 @@ px4_add_board(
dataman
ekf2
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
landing_target_estimator
#load_mon
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
replay
Expand All @@ -50,15 +56,16 @@ px4_add_board(
#sih
simulator
temperature_compensation
uuv_att_control
vmount
vtol_att_control
uuv_att_control

SYSTEMCMDS
#dumpfile
dyn
esc_calib
failure
led_control
#mft
mixer
motor_ramp
motor_test
Expand All @@ -69,6 +76,7 @@ px4_add_board(
pwm
sd_bench
shutdown
system_time
tests # tests and test runner
#top
topic_listener
Expand All @@ -77,6 +85,7 @@ px4_add_board(
work_queue
EXAMPLES
dyn_hello # dynamically loading modules example
fake_magnetometer
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
#hwtest # Hardware test
Expand Down

0 comments on commit b18c6ab

Please sign in to comment.