Skip to content
Snippets Groups Projects
Commit 300e66ae authored by Beat Küng's avatar Beat Küng
Browse files

SYS_COMPANION: deprecate this param

Replaced with the more generic serial config params.

rc.mavlink contains automatic transition support that can be removed after
the next release.
parent f0c0b6f6
No related branches found
No related tags found
No related merge requests found
......@@ -125,7 +125,12 @@ then
param set PWM_RATE 400
param set SENS_BOARD_ROT 18
param set SYS_COMPANION 57600
# TELEM2 config
param set MAV_1_CONFIG 2
param set MAV_1_RATE 5000
param set MAV_1_FORWARD 1
param set SER_TEL2_BAUD 57600
param set VT_TYPE 2
param set VT_MOT_COUNT 4
......
......@@ -53,8 +53,6 @@ then
param set PWM_DISARMED 0
param set PWM_MIN 900
param set PWM_MAX 2100
param set SYS_COMPANION 157600
fi
set MIXER caipi
......
......@@ -84,6 +84,11 @@ then
param set RC5_MIN 1000
param set RC5_REV 1
param set RC5_TRIM 1500
# enable high-speed link on telem 1
param set MAV_0_RATE 80000
param set MAV_0_MODE 2
param set SER_TEL1_BAUD 921600
fi
set MIXER quad_x
......@@ -91,5 +96,3 @@ set MIXER quad_x
set PWM_OUT 1234
set MIXER_AUX none
# enable high-speed link on telem 1
set MAVLINK_F "-d /dev/ttyS1 -b 921600 -r 80000 -m onboard -x"
......@@ -64,7 +64,11 @@ then
param set MPC_Z_VEL_MAX_UP 5.0000
param set MPC_Z_VEL_P 0.8000
param set SYS_COMPANION 921600
# TELEM2 config
param set MAV_1_CONFIG 2
param set MAV_1_RATE 80000
param set MAV_1_FORWARD 1
param set SER_TEL2_BAUD 921600
fi
if param compare SYS_HITL 0
......@@ -78,4 +82,3 @@ fi
set MIXER quad_x
set USE_IO no
set MAVLINK_COMPANION_DEVICE /dev/ttyS1
......@@ -65,8 +65,9 @@ then
param set PWM_RATE 3921
param set SDLOG_PROFILE 1
param set SENS_FLOW_MINRNG 0.05
param set SYS_COMPANION 20
param set SYS_FMU_TASK 1
fi
......@@ -74,3 +75,7 @@ fi
set PWM_DISARMED none
set PWM_MAX none
set PWM_MIN none
syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
#!nsh
#
# MAVLINK stream startup script.
# MAVLink startup script.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
# NOTE: Normal mode uses baud rate of 57600 (default) and data rate of 1000 bytes/s.
#
###############################################################################
# Begin Setup for board specific configurations. #
###############################################################################
if ! ver hwcmp AEROFC_V1
then
# Start MAVLink
# Start MAVLink on the USB port
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
if ver hwcmp NXPHLITE_V3
if ver hwcmp PX4FMU_V4
then
set MAVLINK_COMPANION_DEVICE none
set MAVLINK_F "-r 1200 -d /dev/ttyS4"
# Pixracer: start MAVLink on Wifi (ESP8266 port)
mavlink start -r 20000 -b 921600 -d /dev/ttyS0
fi
if ver hwcmp OMNIBUS_F4SD
#
# SYS_COMPANION transition support. Can be removed after the next release (currently at 1.8.0)
#
if param compare SYS_COMPANION 319200
then
set MAVLINK_COMPANION_DEVICE /dev/ttyS1
param set MAV_1_CONFIG 2
param set MAV_1_RATE 1000
param set SER_TEL2_BAUD 19200
param set SYS_COMPANION 0
fi
###############################################################################
# End Setup for board specific configurations. #
###############################################################################
if [ "x${MAVLINK_F}" == xdefault ]
if param compare SYS_COMPANION 519200
then
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
set MAVLINK_F "-r 1200 -f"
if ver hwcmp AEROFC_V1
then
set MAVLINK_F "-r 1200 -d /dev/ttyS3"
# Only start mavlink if the Benewake TFMini or LeddarOne isn't being used
if param greater SENS_EN_TFMINI 0
then
set MAVLINK_F none
fi
if param greater SENS_EN_LEDDAR1 0
then
set MAVLINK_F none
fi
fi
# Use ttyS1 for MAVLink on FMUv4 in addition to ttyS0 (debug)
if ver hwcmp PX4FMU_V4
then
set MAVLINK_F "-r 1200 -d /dev/ttyS1"
# Start MAVLink on Wifi (ESP8266 port)
mavlink start -r 20000 -b 921600 -d /dev/ttyS0
fi
# Use ttyS3 (TELEM4) for MAVLink on FMUv5 in addition to ttyS1 (TELEM1) and ttyS2 (TELEM2)
if ver hwcmp PX4FMU_V5
then
mavlink start -r 2000 -b 57600 -d /dev/ttyS3
fi
if ver hwcmp CRAZYFLIE OMNIBUS_F4SD
then
# Avoid using either of the two available serials
set MAVLINK_F none
fi
param set MAV_1_CONFIG 2
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 [ "x${MAVLINK_F}" != xnone ]
if param compare SYS_COMPANION 338400
then
mavlink start ${MAVLINK_F}
param set MAV_1_CONFIG 2
param set MAV_1_RATE 1000
param set SER_TEL2_BAUD 38400
param set SYS_COMPANION 0
fi
#
# MAVLink onboard / TELEM2
#
# XXX We need a better way for runtime eval of shell variables,
# but this works for now
#----------------------------------------------------------------
#
# Sys companion setups not dependant on MAVLINK_COMPANION_DEVICE
#
if ! param compare SYS_COMPANION 10
if param compare SYS_COMPANION 538400
then
if ver hwcmp PX4FMU_V4 PX4FMU_V4PRO MINDPX_V2
then
# This is TELEM4 on Pixhawk 3 Pro
frsky_telemetry start -d /dev/ttyS6 -t 15
fi
param set MAV_1_CONFIG 2
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 20
if param compare SYS_COMPANION 57600
then
syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
param set MAV_1_CONFIG 2
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 6460800
if param compare SYS_COMPANION 157600
then
micrortps_client start -t UART -d /dev/ttyS2 -b 460800
param set MAV_1_CONFIG 2
param set MAV_1_MODE 3
param set MAV_1_RATE 1000
param set SER_TEL2_BAUD 57600
param set SYS_COMPANION 0
fi
#----------------------------------------------------------------
#
# Sys companion setups dependant on MAVLINK_COMPANION_DEVICE
#
if [ "x${MAVLINK_COMPANION_DEVICE}" != xnone ]
if param compare SYS_COMPANION 257600
then
if param compare SYS_COMPANION 10
then
frsky_telemetry start -d ${MAVLINK_COMPANION_DEVICE}
fi
#
# 19200 Baud Rate.
#
if param compare SYS_COMPANION 319200
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 19200 -r 1000 -f
fi
if param compare SYS_COMPANION 519200
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 19200 -m minimal -r 1000
fi
#
# 38400 Baud Rate.
#
if param compare SYS_COMPANION 338400
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 38400 -r 1000 -f
fi
if param compare SYS_COMPANION 538400
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 38400 -m minimal -r 1000
fi
#
# 57600 Baud Rate.
#
if param compare SYS_COMPANION 57600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 57600 -m onboard -r 5000 -x -f
fi
if param compare SYS_COMPANION 157600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 57600 -m osd -r 1000
fi
if param compare SYS_COMPANION 257600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 57600 -m magic -r 5000 -x -f
fi
if param compare SYS_COMPANION 357600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 57600 -r 1000 -f
fi
if param compare SYS_COMPANION 557600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 57600 -m minimal -r 1000
fi
#
# 115200 Baud Rate.
#
if param compare SYS_COMPANION 3115200
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 115200 -r 1000 -f
fi
if param compare SYS_COMPANION 4115200
then
usleep 200000 # add a sleep here to make sure that the module is powered
if iridiumsbd start -d ${MAVLINK_COMPANION_DEVICE}
then
mavlink start -d /dev/iridium -m iridium -b 115200
else
tune_control play -t 20
fi
fi
if param compare SYS_COMPANION 5115200
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 115200 -m minimal -r 1000
fi
#
# 460800 Baud Rate.
#
if param compare SYS_COMPANION 460800
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 460800 -m onboard -r 5000 -x -f
fi
#
# 921600 Baud Rate.
#
if param compare SYS_COMPANION 921600
then
if ver hwcmp AEROFC_V1
then
if protocol_splitter start ${MAVLINK_COMPANION_DEVICE}
then
mavlink start -d /dev/mavlink -b 921600 -m onboard -r 5000 -x
micrortps_client start -d /dev/rtps -b 921600 -l -1 -s 2000
else
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 921600 -m onboard -r 80000 -x -f
fi
else
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 921600 -m onboard -r 80000 -x -f
fi
fi
if param compare SYS_COMPANION 1921600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 921600 -r 20000
fi
param set MAV_1_CONFIG 2
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 2
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 2
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 2
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 2
param set SYS_COMPANION 0
fi
if param compare SYS_COMPANION 5115200
then
param set MAV_1_CONFIG 2
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 2
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 2
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 2
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 2
param set MAV_1_RATE 140000
param set MAV_1_MODE 2
param set SER_TEL2_BAUD 1500000
param set SYS_COMPANION 0
fi
#
# 1500000 Baud Rate.
#
if param compare SYS_COMPANION 1500000
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 1500000 -m onboard -r 140000 -x -f
fi
fi
\ No newline at end of file
......@@ -74,8 +74,6 @@ set FMU_MODE pwm
set IOFW "/etc/extras/px4io-v2.bin"
set IO_PRESENT no
set LOG_FILE /fs/microsd/bootlog.txt
set MAVLINK_F default
set MAVLINK_COMPANION_DEVICE /dev/ttyS2
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
......@@ -445,13 +443,9 @@ else
set OUTPUT_MODE hil
sensors start -h
commander start --hil
# disable GPS
param set GPS_1_CONFIG 0
else
if ver hwcmp PX4_SAME70XPLAINED_V1
then
gps start -d /dev/ttyS2
else
gps start
fi
sh /etc/init.d/rc.sensors
commander start
fi
......@@ -507,10 +501,16 @@ else
fi
#
# Start mavlink streams.
# Start mavlink streams that are not configurable (e.g. on USB).
#
sh /etc/init.d/rc.mavlink
#
# Start UART/Serial device drivers.
# Note: rc.serial is auto-generated from Tools/serial/generate_config.py
#
sh /etc/init.d/rc.serial
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
......@@ -585,8 +585,6 @@ unset FMU_MODE
unset IOFW
unset IO_PRESENT
unset LOG_FILE
unset MAVLINK_F
unset MAVLINK_COMPANION_DEVICE
unset MAV_TYPE
unset MIXER
unset MIXER_AUX
......
......@@ -109,10 +109,10 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2);
/**
* TELEM2 as companion computer link
* TELEM2 as companion computer link (deprecated)
*
* CHANGING THIS VALUE REQUIRES A RESTART. Configures the baud rate of the TELEM2 connector as
* companion computer interface.
* This parameter is deprecated. Do not change it, use the more generic serial
* configuration parameters instead.
*
* @value 0 Disabled
* @value 10 FrSky Telemetry
......@@ -139,7 +139,7 @@ PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2);
* @reboot_required true
* @group System
*/
PARAM_DEFINE_INT32(SYS_COMPANION, 157600);
PARAM_DEFINE_INT32(SYS_COMPANION, 0);
/**
* Parameter version
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment