Skip to content

Commit

Permalink
Add support for ModalAI FC1
Browse files Browse the repository at this point in the history
  • Loading branch information
modaltb authored and dagar committed Oct 19, 2019
1 parent 070d754 commit 3bbf1cc
Show file tree
Hide file tree
Showing 22 changed files with 3,686 additions and 1 deletion.
3 changes: 2 additions & 1 deletion .ci/Jenkinsfile-compile
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ pipeline {
"px4_fmu-v5_default", "px4_fmu-v5_fixedwing", "px4_fmu-v5_multicopter", "px4_fmu-v5_rover", "px4_fmu-v5_rtps", "px4_fmu-v5_stackcheck",
"px4_fmu-v5x_default",
"intel_aerofc-v1_default", "auav_x21_default", "av_x-v1_default", "bitcraze_crazyflie_default", "airmind_mindpx-v2_default",
"holybro_kakutef7", "mro_ctrl-zero-f7_default", "nxp_fmuk66-v3_default", "omnibus_f4sd_default", "uvify_core_default"],
"holybro_kakutef7", "modalai_fc-v1_default", "mro_ctrl-zero-f7_default", "nxp_fmuk66-v3_default", "omnibus_f4sd_default",
"uvify_core_default"],
image: docker_images.nuttx,
archive: true
]
Expand Down
5 changes: 5 additions & 0 deletions .vscode/cmake-variants.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,11 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: intel_aerofc-v1_default
modalai_fc1_default:
short: modalai_fc1_default
buildType: MinSizeRel
settings:
CONFIG: modalai_fc1_default
mro_ctrl-zero-f7_default:
short: mro_ctrl-zero-f7_default
buildType: MinSizeRel
Expand Down
120 changes: 120 additions & 0 deletions boards/modalai/fc-v1/default.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@

px4_add_board(
PLATFORM nuttx
VENDOR modalai
MODEL fc-v1
LABEL default
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
TESTING
UAVCAN_INTERFACES 1

SERIAL_PORTS
GPS1:/dev/ttyS0 # UART1 / J10
TEL1:/dev/ttyS6 # UART7 / J5
TEL2:/dev/ttyS4 # UART5 / J1
TEL3:/dev/ttyS1 # USART2 / J4

DRIVERS
adc
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
gps
imu/bmi088
# TODO imu/icm42688
imu/mpu6000
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
#md25
mkblctrl
#optical_flow # all available optical flow drivers
pca9685
power_monitor/ina226
power_monitor/voxlpm
#protocol_splitter
#pwm_input
pwm_out_sim
px4fmu
#px4io
rc_input
roboclaw
safety_button
tap_esc
telemetry # all available telemetry drivers
test_ppm
#tone_alarm
uavcan

MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
navigator
rover_pos_control
sensors
sih
vmount
vtol_att_control
airspeed_selector

SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
i2cdetect
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
work_queue

EXAMPLES
bottle_drop # OBC challenge
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
hwtest # Hardware test
#matlab_csv_serial
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
rover_steering_control # Rover example app
uuv_example_app
)
13 changes: 13 additions & 0 deletions boards/modalai/fc-v1/firmware.prototype
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
{
"board_id": 41775,
"magic": "PX4FWv1",
"description": "Firmware for the ModalAI Flight Core v1 board",
"image": "",
"build_time": 0,
"summary": "modalaifcv1",
"version": "0.1",
"image_size": 0,
"image_maxsize": 2064384,
"git_identity": "",
"board_revision": 0
}
26 changes: 26 additions & 0 deletions boards/modalai/fc-v1/init/rc.board_defaults
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#!/bin/sh
#
# ModalAI FC-v1 specific board defaults
#------------------------------------------------------------------------------


if [ $AUTOCNF = yes ]
then
# Disable safety switch by default
param set CBRK_IO_SAFETY 22027

#
# TELEM2 /dev/ttyS4
#
# In the VOXL-FMU, this port is connect to the VOXL internally
# In the FMU, this J1 port can connect to the VOXL J12
# By default, we use this UART connection with MAVLink at 921.6kHz
#
param set MAV_1_CONFIG 102 # TELEM2
param set MAV_1_MODE 0 # normal
param set SER_TEL2_BAUD 921600
fi

set LOGGER_BUF 64

safety_button start
7 changes: 7 additions & 0 deletions boards/modalai/fc-v1/init/rc.board_mavlink
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#!/bin/sh
#
# ModalAI FC-v1 specific board MAVLink startup script.
#------------------------------------------------------------------------------

# Start MAVLink on the USB port
mavlink start -d /dev/ttyACM0
28 changes: 28 additions & 0 deletions boards/modalai/fc-v1/init/rc.board_sensors
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#!/bin/sh
#
# ModalAI FC-v1 specific board sensors init
#------------------------------------------------------------------------------

# Start Digital power monitors
voxlpm -R start

# Internal SPI bus ICM-20602
mpu6000 -R 2 -s -T 20602 start

# Internal SPI bus ICM-42688
# TODO

# Internal SPI bus BMI088 accel
bmi088 -A start

# Internal SPI bus BMI088 gyro
bmi088 -G start

# Possible external compasses
ist8310 -C -b 1 start
ist8310 -C -b 2 start
hmc5883 -C -T -X start
qmc5883 -X start

# Internal I2C Baro
bmp388 -I start
17 changes: 17 additions & 0 deletions boards/modalai/fc-v1/nuttx-config/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
config BOARD_HAS_PROBES
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
default y
---help---
This board provides GPIO FMU-CH1-8, CAP1 as PROBE_1-9 to provide timing signals from selected drivers.

config BOARD_USE_PROBES
bool "Enable the use the board provided FMU-CH1-8, CAP1 as PROBE_1-9"
default n
depends on BOARD_HAS_PROBES

---help---
Select to use GPIO FMU-CH1-8, CAP1 to provide timing signals from selected drivers.
Loading

0 comments on commit 3bbf1cc

Please sign in to comment.