mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
* MC_HTE: unitialize with hover_thrust parameter * MC_HTE: constrain hover thrust setter between 0.1 and 0.9 * MC_HTE: integrate with land detector and velocity controller * MCHoverThrustEstimator: Always publish an estimate even when not fusing measurements. This is required as the land detector and the position controller need to receive a hover thrust value. * MC_HTE: use altitude agl threshold to start the estimator local_position.z is relative to the origin of the EKF while dist_bottom is above ground Co-authored-by: bresch <brescianimathieu@gmail.com>
91 lines
1.2 KiB
Bash
91 lines
1.2 KiB
Bash
#!/bin/sh
|
|
# PX4 commands need the 'px4-' prefix in bash.
|
|
# (px4-alias.sh is expected to be in the PATH)
|
|
. px4-alias.sh
|
|
|
|
# navio config for simple testing
|
|
|
|
uorb start
|
|
|
|
if [ -f eeprom/parameters ]
|
|
then
|
|
param load
|
|
fi
|
|
param set SYS_AUTOSTART 4001
|
|
param set MAV_BROADCAST 1
|
|
param set MAV_TYPE 2
|
|
param set BAT_CNT_V_VOLT 0.001
|
|
param set BAT_CNT_V_CURR 0.001
|
|
|
|
dataman start
|
|
|
|
mpu9250 -R 8 start
|
|
lsm9ds1 -R 4 start
|
|
lsm9ds1_mag -R 4 start
|
|
ms5611 start
|
|
|
|
navio_rgbled start
|
|
|
|
adc start
|
|
battery_status start
|
|
|
|
gps start -d /dev/spidev0.0 -i spi -p ubx
|
|
rc_update start
|
|
sensors start
|
|
commander start
|
|
navigator start
|
|
ekf2 start
|
|
land_detector start multicopter
|
|
mc_hover_thrust_estimator start
|
|
mc_pos_control start
|
|
mc_att_control start
|
|
|
|
mavlink start -x -u 14556 -r 1000000
|
|
|
|
if [ -f /dev/ttyUSB0 ]
|
|
then
|
|
mavlink start -x -d /dev/ttyUSB0
|
|
fi
|
|
|
|
navio_sysfs_rc_in start
|
|
linux_pwm_out start
|
|
|
|
logger start -t -b 200
|
|
|
|
mavlink boot_complete
|
|
|
|
sleep 5
|
|
|
|
ver all
|
|
sleep 1
|
|
commander check
|
|
sleep 1
|
|
dataman status
|
|
sleep 1
|
|
ekf2 status
|
|
sleep 1
|
|
logger status
|
|
sleep 1
|
|
mavlink status
|
|
sleep 1
|
|
mavlink status streams
|
|
sleep 1
|
|
param show
|
|
sleep 1
|
|
param status
|
|
sleep 1
|
|
pwm info
|
|
sleep 1
|
|
sensors status
|
|
sleep 1
|
|
perf
|
|
sleep 1
|
|
perf latency
|
|
sleep 1
|
|
work_queue status
|
|
sleep 1
|
|
uorb top -1
|
|
sleep 1
|
|
|
|
shutdown
|