diff --git a/ROMFS/px4fmu_common/init.d/13013_deltaquad b/ROMFS/px4fmu_common/init.d/13013_deltaquad index c01f83f708..cd7c4c1626 100644 --- a/ROMFS/px4fmu_common/init.d/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/13013_deltaquad @@ -127,7 +127,7 @@ then param set SENS_BOARD_ROT 18 # TELEM2 config - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 5000 param set MAV_1_FORWARD 1 param set SER_TEL2_BAUD 57600 diff --git a/ROMFS/px4fmu_common/init.d/4070_aerofc b/ROMFS/px4fmu_common/init.d/4070_aerofc index 07b43532d1..bee3fa1003 100644 --- a/ROMFS/px4fmu_common/init.d/4070_aerofc +++ b/ROMFS/px4fmu_common/init.d/4070_aerofc @@ -65,7 +65,7 @@ then param set MPC_Z_VEL_P 0.8000 # TELEM2 config - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 80000 param set MAV_1_FORWARD 1 param set SER_TEL2_BAUD 921600 diff --git a/ROMFS/px4fmu_common/init.d/rc.mavlink b/ROMFS/px4fmu_common/init.d/rc.mavlink index fc3a78790a..2e19da82ec 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mavlink +++ b/ROMFS/px4fmu_common/init.d/rc.mavlink @@ -23,14 +23,14 @@ fi # if param compare SYS_COMPANION 319200 then - param set MAV_1_CONFIG 2 + 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 2 + param set MAV_1_CONFIG 102 param set MAV_1_MODE 7 param set MAV_1_RATE 1000 param set SER_TEL2_BAUD 19200 @@ -38,14 +38,14 @@ then fi if param compare SYS_COMPANION 338400 then - param set MAV_1_CONFIG 2 + 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 2 + param set MAV_1_CONFIG 102 param set MAV_1_MODE 7 param set MAV_1_RATE 1000 param set SER_TEL2_BAUD 38400 @@ -53,7 +53,7 @@ then fi if param compare SYS_COMPANION 57600 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_MODE 2 param set MAV_1_RATE 5000 param set SER_TEL2_BAUD 57600 @@ -61,7 +61,7 @@ then fi if param compare SYS_COMPANION 157600 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_MODE 3 param set MAV_1_RATE 1000 param set SER_TEL2_BAUD 57600 @@ -69,7 +69,7 @@ then fi if param compare SYS_COMPANION 257600 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_MODE 4 param set MAV_1_RATE 5000 param set SER_TEL2_BAUD 57600 @@ -77,14 +77,14 @@ then fi if param compare SYS_COMPANION 357600 then - param set MAV_1_CONFIG 2 + 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 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 1000 param set MAV_1_MODE 7 param set SER_TEL2_BAUD 57600 @@ -92,7 +92,7 @@ then fi if param compare SYS_COMPANION 3115200 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 1000 param set SER_TEL2_BAUD 115200 param set SYS_COMPANION 0 @@ -100,12 +100,12 @@ fi if param compare SYS_COMPANION 4115200 then # Iridium - param set ISBD_CONFIG 2 + param set ISBD_CONFIG 102 param set SYS_COMPANION 0 fi if param compare SYS_COMPANION 5115200 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 1000 param set MAV_1_MODE 7 param set SER_TEL2_BAUD 115200 @@ -113,7 +113,7 @@ then fi if param compare SYS_COMPANION 460800 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 5000 param set MAV_1_MODE 2 param set SER_TEL2_BAUD 460800 @@ -121,7 +121,7 @@ then fi if param compare SYS_COMPANION 921600 then - param set MAV_1_CONFIG 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 80000 param set MAV_1_MODE 2 param set SER_TEL2_BAUD 921600 @@ -129,14 +129,14 @@ then fi if param compare SYS_COMPANION 1921600 then - param set MAV_1_CONFIG 2 + 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 2 + param set MAV_1_CONFIG 102 param set MAV_1_RATE 140000 param set MAV_1_MODE 2 param set SER_TEL2_BAUD 1500000 diff --git a/Tools/serial/generate_config.py b/Tools/serial/generate_config.py index 2f642c16ee..71a7464085 100755 --- a/Tools/serial/generate_config.py +++ b/Tools/serial/generate_config.py @@ -26,41 +26,88 @@ except: # with QGC (parameter metadata) serial_ports = { # index 0 means disabled + + # Generic +# "URT1": { +# "label": "UART 1", +# "index": 1, +# "default_baudrate": 57600, +# }, +# "URT2": { +# "label": "UART 2", +# "index": 2, +# "default_baudrate": 57600, +# }, +# "URT3": { +# "label": "UART 3", +# "index": 3, +# "default_baudrate": 57600, +# }, +# "URT4": { +# "label": "UART 4", +# "index": 4, +# "default_baudrate": 57600, +# }, +# "URT5": { +# "label": "UART 5", +# "index": 5, +# "default_baudrate": 57600, +# }, + "URT6": { + "label": "UART 6", + "index": 6, + "default_baudrate": 57600, + }, +# "URT7": { +# "label": "UART 7", +# "index": 7, +# "default_baudrate": 57600, +# }, +# "URT8": { +# "label": "UART 8", +# "index": 8, +# "default_baudrate": 57600, +# }, +# "URT9": { +# "label": "UART 9", +# "index": 9, +# "default_baudrate": 57600, +# }, + + # Telemetry Ports "TEL1": { # telemetry link "label": "TELEM 1", - "index": 1, + "index": 101, "default_baudrate": 57600, }, "TEL2": { # companion port "label": "TELEM 2", - "index": 2, + "index": 102, "default_baudrate": 921600, }, "TEL3": { "label": "TELEM 3", - "index": 3, + "index": 103, "default_baudrate": 57600, }, "TEL4": { "label": "TELEM/SERIAL 4", - "index": 4, + "index": 104, "default_baudrate": 57600, }, + + # GPS Ports "GPS1": { "label": "GPS 1", - "index": 5, + "index": 201, "default_baudrate": 0, }, "GPS2": { "label": "GPS 2", - "index": 6, - "default_baudrate": 0, - }, - "URT6": { # for Omnibus - "label": "UART 6", - "index": 7, + "index": 202, "default_baudrate": 0, }, + } parser = argparse.ArgumentParser(description='Generate Serial params & startup script')