mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
MAVLink: Reduce default link data rates
This commit is contained in:
parent
f91be99a4e
commit
adda7702f9
37
ROMFS/px4fmu_common/init.d/10020_3dr_quad
Normal file
37
ROMFS/px4fmu_common/init.d/10020_3dr_quad
Normal file
@ -0,0 +1,37 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
# @maintainer Anton Babushkin <anton@px4.io>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
# TODO tune roll/pitch separately
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.004
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.05
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 2.5
|
||||
param set MC_YAWRATE_P 0.25
|
||||
param set MC_YAWRATE_I 0.25
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_V_SCALING 0.00989
|
||||
param set BAT_C_SCALING 0.0124
|
||||
fi
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
set PWM_MIN 1100
|
||||
set PWM_MAX 1950
|
||||
@ -468,13 +468,13 @@ then
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
set MAVLINK_F "-r 5000 -d /dev/ttyS0"
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS0"
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
# Start MAVLink on default port: ttyS1
|
||||
set MAVLINK_F "-r 5000"
|
||||
set MAVLINK_F "-r 1200"
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user