2018-08-06 09:24:15 -03:00
|
|
|
#!/usr/bin/bash
|
|
|
|
# PX4 commands need the 'px4-' prefix in bash.
|
|
|
|
# (px4-alias.sh is expected to be in the PATH)
|
|
|
|
source px4-alias.sh
|
|
|
|
|
2018-07-24 01:04:47 -03:00
|
|
|
# config for a quad
|
|
|
|
# modified from ../rpi/px4.config
|
|
|
|
|
|
|
|
uorb start
|
|
|
|
param load
|
|
|
|
|
|
|
|
# Auto-start script index. Defines the auto-start script used to bootstrap the system.
|
|
|
|
# It seems that SYS_AUTOSTART does not work as intended on posix platform.
|
|
|
|
# For now, find the corresponding settings, and manually set them in ground control.
|
|
|
|
#
|
|
|
|
# 4001: Generic Quadrotor X; 4011: DJI Flame Wheel F450
|
|
|
|
param set SYS_AUTOSTART 4011
|
|
|
|
|
|
|
|
# DJI ESCs do not support calibration and need higher PWM_MIN
|
|
|
|
# http://www.dji.com/e2000/info indicates E2000 Operating Pulse Width: 1120 to 1920 μs
|
|
|
|
# It seems that all latest DJI ESC have the same range.
|
|
|
|
# Note that the setting here applies to all PWM channels.
|
|
|
|
# param set PWM_MIN 1120
|
|
|
|
# param set PWM_MAX 1920
|
|
|
|
# Not using DJI 430 LITE ESC anymore due to its hiccups:
|
|
|
|
# each random motor stop would cause a scary flip in the fly
|
|
|
|
# Replacing with 4 BLHeli32 (Wraith32 V2) ESCs solved the main problem in BBBlue porting
|
|
|
|
|
|
|
|
# Broadcast heartbeats on local network. This allows a ground control station
|
|
|
|
# to automatically find the drone on the local network.
|
|
|
|
param set MAV_BROADCAST 1
|
|
|
|
|
|
|
|
# MAV_TYPE: 1 Fixed wing aircraft, 2 Quadrotor
|
|
|
|
param set MAV_TYPE 2
|
|
|
|
|
|
|
|
# Set multicopter estimator group, 1 local_position_estimator, attitude_estimator_q, 2 ekf2
|
|
|
|
param set SYS_MC_EST_GROUP 2
|
|
|
|
|
|
|
|
# Three possible main power battery sources for BBBlue:
|
|
|
|
# 1. onboard 2S LiPo battery connector, which is connect to ADC channel 6
|
|
|
|
# 2. onboard 9-18V DC Jack, which is connect to ADC channel 5. This is the board default.
|
|
|
|
# 3. other power source (e.g., LiPo battery more than 4S/18V).
|
|
|
|
# Scale the voltage to below 1.8V and connect it to ADC channel # 0, 1, 2 or 3.
|
|
|
|
param set BAT_ADC_CHANNEL 5
|
|
|
|
|
|
|
|
# 12-bit 1.8V ADC, 1.8V / 2^12 = 0.000439453125 V/CNT
|
|
|
|
param set BAT_CNT_V_VOLT 0.0004394531
|
|
|
|
|
|
|
|
# Battery voltage scale factor, from BBBlue schematics: (4.7K + 47K) / 4.7K = 11
|
|
|
|
param set BAT_V_DIV 11.0
|
|
|
|
|
|
|
|
#param set BAT_CNT_V_CURR 0.001
|
|
|
|
#param set BAT_A_PER_V 15.391030303
|
|
|
|
|
|
|
|
dataman start
|
|
|
|
|
|
|
|
df_bmp280_wrapper start -D /dev/i2c-2
|
|
|
|
|
|
|
|
df_mpu9250_wrapper start
|
|
|
|
# options: -R rotation
|
|
|
|
|
|
|
|
gps start -d /dev/ttyS2 -s -p ubx
|
|
|
|
|
|
|
|
#rgbled start -b 1
|
|
|
|
bbblue_adc start
|
|
|
|
bbblue_adc test
|
|
|
|
|
|
|
|
sensors start
|
|
|
|
commander start
|
|
|
|
navigator start
|
|
|
|
ekf2 start
|
2018-07-31 02:06:58 -03:00
|
|
|
land_detector start multicopter
|
2018-07-24 01:04:47 -03:00
|
|
|
|
|
|
|
mc_pos_control start
|
|
|
|
mc_att_control start
|
|
|
|
#fw_att_control start
|
|
|
|
#fw_pos_control_l1 start
|
|
|
|
|
2018-07-28 22:55:08 -03:00
|
|
|
mavlink start -n SoftAp -x -u 14556 -r 1000000
|
2018-07-24 01:04:47 -03:00
|
|
|
# -n name of wifi interface: SoftAp, wlan or your custom interface,
|
2018-07-28 22:55:08 -03:00
|
|
|
# e.g., -n SoftAp . The default is wlan
|
2018-07-24 01:04:47 -03:00
|
|
|
|
|
|
|
sleep 1
|
|
|
|
|
|
|
|
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
|
|
|
|
mavlink stream -u 14556 -s ATTITUDE -r 20
|
|
|
|
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
|
|
|
|
|
|
|
|
linux_sbus start -d /dev/ttyS4 -c 16
|
|
|
|
# DSM2 port is mapped to /dev/ttyS4 (default for linux_sbus)
|
|
|
|
|
|
|
|
# default: ROMFS/px4fmu_common/mixers/quad_x.main.mix, 8 output channels
|
|
|
|
linux_pwm_out start -p bbblue_rc -m ROMFS/px4fmu_common/mixers/quad_x.main.mix
|
|
|
|
#linux_pwm_out start -p bbblue_rc -m ROMFS/px4fmu_common/mixers/AETRFG.main.mix
|
|
|
|
|
|
|
|
logger start -t -b 200
|
|
|
|
mavlink boot_complete
|