diff --git a/ROMFS/px4fmu_common/init.d/rc.mavlink b/ROMFS/px4fmu_common/init.d/rc.mavlink index 4c9f58c40b..451de95649 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mavlink +++ b/ROMFS/px4fmu_common/init.d/rc.mavlink @@ -11,128 +11,3 @@ then 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 - diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index c2fa371eaa..f0041bef89 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -110,39 +110,6 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); */ PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2); -/** - * TELEM2 as companion computer link (deprecated) - * - * This parameter is deprecated and will be removed after 1.9.0. Use the generic serial - * configuration parameters instead (e.g. MAV_0_CONFIG, MAV_0_MODE, etc.). - * - * @value 0 Disabled - * @value 10 FrSky Telemetry - * @value 20 Crazyflie (Syslink) - * @value 921600 Companion Link (921600 baud, 8N1) - * @value 57600 Companion Link (57600 baud, 8N1) - * @value 1500000 Companion Link (1500000 baud, 8N1) - * @value 157600 OSD (57600 baud, 8N1) - * @value 257600 Command Receiver (57600 baud, 8N1) - * @value 319200 Normal Telemetry (19200 baud, 8N1) - * @value 338400 Normal Telemetry (38400 baud, 8N1) - * @value 357600 Normal Telemetry (57600 baud, 8N1) - * @value 3115200 Normal Telemetry (115200 baud, 8N1) - * @value 4115200 Iridium Telemetry (115200 baud, 8N1) - * @value 519200 Minimal Telemetry (19200 baud, 8N1) - * @value 538400 Minimal Telemetry (38400 baud, 8N1) - * @value 557600 Minimal Telemetry (57600 baud, 8N1) - * @value 5115200 Minimal Telemetry (115200 baud, 8N1) - * @value 6460800 RTPS Client (460800 baud) - * @value 1921600 ESP8266 (921600 baud, 8N1) - * - * @min 0 - * @max 6460800 - * @reboot_required true - * @group System - */ -PARAM_DEFINE_INT32(SYS_COMPANION, 0); - /** * Parameter version *