From e7b30a0085a6476c9100c1ed6bec9412dc22173d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Nov 2021 10:48:42 +1100 Subject: [PATCH] sim_vehicle.py: correct setting of udpclient ports --- Tools/autotest/sim_vehicle.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index e6bc885667..3e73d16073 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -694,10 +694,6 @@ def start_vehicle(binary, opts, stuff, spawns=None): if path is not None: cmd.extend(["--defaults", path]) - if opts.mcast: - cmd.extend(["--uartA", "mcast:"]) - elif opts.udp: - cmd.extend(["--uartA", "udpclient:127.0.0.1:" + str(5760+cmd_opts.instance*10)]) if cmd_opts.start_time is not None: # Parse start_time into a double precision number specifying seconds since 1900. @@ -714,6 +710,10 @@ def start_vehicle(binary, opts, stuff, spawns=None): c = ["-I" + str(i)] if spawns is not None: c.extend(["--home", spawns[i]]) + if opts.mcast: + c.extend(["--uartA", "mcast:"]) + elif opts.udp: + c.extend(["--uartA", "udpclient:127.0.0.1:" + str(5760+i*10)]) if opts.auto_sysid: if opts.sysid is not None: raise ValueError("Can't use auto-sysid and sysid together")