You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
138 lines
3.0 KiB
138 lines
3.0 KiB
#!/bin/sh |
|
# |
|
# MAVLink startup script. |
|
# |
|
# NOTE: Script variables are declared/initialized/unset in the rcS script. |
|
# |
|
|
|
if ! ver hwcmp INTEL_AEROFC_V1 |
|
then |
|
# Start MAVLink on the USB port |
|
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x |
|
fi |
|
|
|
# |
|
# SYS_COMPANION transition support. Can be removed after the next release (currently at 1.8.0) |
|
# |
|
if param compare SYS_COMPANION 319200 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 19200 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 519200 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_MODE 7 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 19200 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 338400 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 38400 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 538400 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_MODE 7 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 38400 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 57600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_MODE 2 |
|
param set MAV_1_RATE 5000 |
|
param set SER_TEL2_BAUD 57600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 157600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_MODE 3 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 57600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 257600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_MODE 4 |
|
param set MAV_1_RATE 5000 |
|
param set SER_TEL2_BAUD 57600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 357600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 57600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 557600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set MAV_1_MODE 7 |
|
param set SER_TEL2_BAUD 57600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 3115200 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set SER_TEL2_BAUD 115200 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 4115200 |
|
then |
|
# Iridium |
|
param set ISBD_CONFIG 102 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 5115200 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 1000 |
|
param set MAV_1_MODE 7 |
|
param set SER_TEL2_BAUD 115200 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 460800 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 5000 |
|
param set MAV_1_MODE 2 |
|
param set SER_TEL2_BAUD 460800 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 921600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 80000 |
|
param set MAV_1_MODE 2 |
|
param set SER_TEL2_BAUD 921600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 1921600 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 20000 |
|
param set SER_TEL2_BAUD 921600 |
|
param set SYS_COMPANION 0 |
|
fi |
|
if param compare SYS_COMPANION 1500000 |
|
then |
|
param set MAV_1_CONFIG 102 |
|
param set MAV_1_RATE 140000 |
|
param set MAV_1_MODE 2 |
|
param set SER_TEL2_BAUD 1500000 |
|
param set SYS_COMPANION 0 |
|
fi |
|
|
|
|