Browse Source

MAVLink: Reduce default link data rates

sbg
Lorenz Meier 10 years ago
parent
commit
d19718a23b
  1. 37
      ROMFS/px4fmu_common/init.d/10020_3dr_quad
  2. 4
      ROMFS/px4fmu_common/init.d/rcS

37
ROMFS/px4fmu_common/init.d/10020_3dr_quad

@ -0,0 +1,37 @@ @@ -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

4
ROMFS/px4fmu_common/init.d/rcS

@ -457,13 +457,13 @@ then @@ -457,13 +457,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…
Cancel
Save