Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
|
|
|
|
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
|
|
|
|
|
|
|
|
# user-configurable UART ports
|
|
|
|
set(board_serial_ports
|
|
|
|
TEL2:/dev/ttyS1
|
|
|
|
URT6:/dev/ttyS2)
|
|
|
|
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
set(config_module_list
|
|
|
|
#
|
|
|
|
# Board support modules
|
|
|
|
#
|
|
|
|
drivers/barometer/bmp280
|
|
|
|
#drivers/differential_pressure
|
|
|
|
#drivers/distance_sensor
|
|
|
|
drivers/magnetometer/hmc5883
|
|
|
|
drivers/telemetry/frsky_telemetry
|
|
|
|
drivers/imu/mpu6000
|
|
|
|
|
|
|
|
#drivers/batt_smbus
|
|
|
|
#drivers/blinkm
|
|
|
|
#drivers/camera_trigger
|
|
|
|
drivers/gps
|
|
|
|
drivers/px4flow
|
|
|
|
drivers/px4fmu
|
|
|
|
drivers/rc_input
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
drivers/rgbled
|
|
|
|
drivers/stm32
|
|
|
|
drivers/stm32/adc
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
#drivers/stm32/tone_alarm
|
|
|
|
modules/sensors
|
|
|
|
|
|
|
|
#
|
|
|
|
# System commands
|
|
|
|
#
|
|
|
|
#systemcmds/bl_update
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
systemcmds/config
|
|
|
|
systemcmds/esc_calib
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
systemcmds/hardfault_log
|
|
|
|
systemcmds/led_control
|
|
|
|
systemcmds/mixer
|
|
|
|
#systemcmds/motor_ramp
|
|
|
|
#systemcmds/mtd
|
|
|
|
systemcmds/nshterm
|
|
|
|
systemcmds/param
|
|
|
|
systemcmds/perf
|
|
|
|
systemcmds/pwm
|
|
|
|
systemcmds/reboot
|
|
|
|
systemcmds/sd_bench
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
systemcmds/top
|
|
|
|
systemcmds/topic_listener
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
systemcmds/tune_control
|
|
|
|
systemcmds/ver
|
|
|
|
|
|
|
|
##
|
|
|
|
## Testing
|
|
|
|
##
|
|
|
|
#drivers/distance_sensor/sf0x/sf0x_tests
|
|
|
|
#drivers/test_ppm
|
|
|
|
##lib/rc/rc_tests
|
|
|
|
#modules/commander/commander_tests
|
|
|
|
#lib/controllib/controllib_test
|
|
|
|
#modules/mavlink/mavlink_tests
|
|
|
|
#modules/mc_pos_control/mc_pos_control_tests
|
|
|
|
#modules/uORB/uORB_tests
|
|
|
|
#systemcmds/tests
|
|
|
|
|
|
|
|
#
|
|
|
|
# General system control
|
|
|
|
#
|
|
|
|
#modules/camera_feedback
|
|
|
|
modules/commander
|
|
|
|
modules/events
|
|
|
|
modules/gpio_led
|
|
|
|
modules/land_detector
|
|
|
|
modules/load_mon
|
|
|
|
modules/mavlink
|
|
|
|
modules/navigator
|
|
|
|
|
|
|
|
#
|
|
|
|
# Estimation modules
|
|
|
|
#
|
|
|
|
modules/attitude_estimator_q
|
|
|
|
modules/ekf2
|
|
|
|
modules/landing_target_estimator
|
|
|
|
modules/local_position_estimator
|
|
|
|
#modules/wind_estimator
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
|
|
|
|
#
|
|
|
|
# Vehicle Control
|
|
|
|
#
|
|
|
|
#modules/fw_att_control
|
|
|
|
#modules/fw_pos_control_l1
|
|
|
|
#modules/gnd_att_control
|
|
|
|
#modules/gnd_pos_control
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
modules/mc_att_control
|
|
|
|
modules/mc_pos_control
|
|
|
|
#modules/vtol_att_control
|
Initial omnibusf4sd target support
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
7 years ago
|
|
|
|
|
|
|
#
|
|
|
|
# Logging
|
|
|
|
#
|
|
|
|
modules/logger
|
|
|
|
|
|
|
|
#
|
|
|
|
# Library modules
|
|
|
|
#
|
|
|
|
modules/dataman
|
|
|
|
|
|
|
|
##
|
|
|
|
## OBC challenge
|
|
|
|
##
|
|
|
|
#examples/bottle_drop
|
|
|
|
|
|
|
|
##
|
|
|
|
## Rover apps
|
|
|
|
##
|
|
|
|
#examples/rover_steering_control
|
|
|
|
|
|
|
|
##
|
|
|
|
## Segway
|
|
|
|
##
|
|
|
|
#examples/segway
|
|
|
|
|
|
|
|
##
|
|
|
|
## Demo apps
|
|
|
|
##
|
|
|
|
|
|
|
|
## Tutorial code from
|
|
|
|
## https://px4.io/dev/px4_simple_app
|
|
|
|
#examples/px4_simple_app
|
|
|
|
|
|
|
|
## Tutorial code from
|
|
|
|
## https://px4.io/dev/debug_values
|
|
|
|
#examples/px4_mavlink_debug
|
|
|
|
|
|
|
|
## Tutorial code from
|
|
|
|
## https://px4.io/dev/example_fixedwing_control
|
|
|
|
#examples/fixedwing_control
|
|
|
|
|
|
|
|
## Hardware test
|
|
|
|
#examples/hwtest
|
|
|
|
)
|