SITL: remove references to legacy UART order incl. sim arguments

This commit is contained in:
Thomas Watson 2023-12-11 11:13:24 -06:00 committed by Andrew Tridgell
parent 9044632315
commit f6ea8201b2
42 changed files with 49 additions and 49 deletions

View File

@ -164,7 +164,7 @@ void ADSB::send_report(const class Aircraft &aircraft)
{
if (AP_HAL::millis() < 10000) {
// simulated aircraft don't appear until 10s after startup. This avoids a windows
// threading issue with non-blocking sockets and the initial wait on uartA
// threading issue with non-blocking sockets and the initial wait on SERIAL0
return;
}

View File

@ -14,7 +14,7 @@
*/
/*
Dump logged AIS data to the serial port
./Tools/autotest/sim_vehicle.py -v Rover -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0
./Tools/autotest/sim_vehicle.py -v Rover -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0
param set SERIAL5_PROTOCOL 40
param set AIS_TYPE 1

View File

@ -14,7 +14,7 @@
*/
/*
Dump logged AIS data to the serial port
./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0
./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0
param set SERIAL5_PROTOCOL 40
param set AIS_TYPE 1

View File

@ -15,7 +15,7 @@
/*
Simulated CRSF device
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:crsf --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:crsf --speedup=1
param set SERIAL5_PROTOCOL 23
reboot

View File

@ -15,7 +15,7 @@
/*
simulate Hirth EFI system
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:hirth --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:hirth --speedup=1
param set SERIAL5_PROTOCOL 24
param set SIM_EFI_TYPE 6
param set EFI_TYPE 6

View File

@ -15,7 +15,7 @@
/*
simulate MegaSquirt EFI system
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:megasquirt --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:megasquirt --speedup=1
param set SERIAL5_PROTOCOL 24
param set SIM_EFI_TYPE 1
param set EFI_TYPE 1

View File

@ -15,7 +15,7 @@
/*
Simulator for the FETtecOneWire ESCs
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:fetteconewireesc --speedup=1 --console
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:fetteconewireesc --speedup=1 --console
param set SERIAL5_PROTOCOL 38
param set SERIAL5_BAUD 500000

View File

@ -15,7 +15,7 @@
/*
Simulated Frsky D device
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:frsky-d --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:frsky-d --speedup=1
param set SERIAL5_PROTOCOL 3
reboot

View File

@ -18,7 +18,7 @@
Usage example:
param set SERIAL5_PROTOCOL 5
sim_vehicle.py -D --console --map -A --uartB=sim:gps:2
sim_vehicle.py -D --console --map -A --serial5=sim:gps:2
*/
#pragma once

View File

@ -258,7 +258,7 @@ void Gimbal::send_report(void)
if (now < 10000) {
// don't send gimbal reports until 10s after startup. This
// avoids a windows threading issue with non-blocking sockets
// and the initial wait on uartA
// and the initial wait on SERIAL0
return;
}
if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {

View File

@ -15,7 +15,7 @@
/*
Simulator for the IntelligentEnergy 2.4kW FuelCell
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:ie24 --speedup=1 --console
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:ie24 --speedup=1 --console
param set SERIAL5_PROTOCOL 30 # Generator
param set SERIAL5_BAUD 115200

View File

@ -602,7 +602,7 @@ void Morse::send_report(void)
if (now < 10000) {
// don't send lidar reports until 10s after startup. This
// avoids a windows threading issue with non-blocking sockets
// and the initial wait on uartA
// and the initial wait on SERIAL0
return;
}
#endif

View File

@ -15,7 +15,7 @@
/*
Simulator for the LightWare S45B proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0
param set SERIAL5_PROTOCOL 11 # proximity
param set PRX1_TYPE 8 # s45b

View File

@ -17,7 +17,7 @@
/*
Simulator for the RPLidarA2 proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map
param set SERIAL5_PROTOCOL 11
param set PRX1_TYPE 5

View File

@ -15,7 +15,7 @@
/*
Simulator for the RPLidarA2 proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map
param set SERIAL5_PROTOCOL 11
param set PRX1_TYPE 5

View File

@ -15,7 +15,7 @@
/*
Simulator for the RPLidarA2 proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map
param set SERIAL5_PROTOCOL 11
param set PRX1_TYPE 5

View File

@ -15,7 +15,7 @@
/*
Simulator for the TeraRangerTower proximity sensor
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0
param set SERIAL5_PROTOCOL 11
param set PRX1_TYPE 3 # terarangertower

View File

@ -15,7 +15,7 @@
/*
Simulator for the BLping rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --uartF=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --serial5=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 23

View File

@ -15,7 +15,7 @@
/*
Simulator for the Benewake TF02 RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf02 --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf02 --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 19

View File

@ -15,7 +15,7 @@
/*
Simulator for the Benewake TF03 RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf03 --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf03 --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 27

View File

@ -15,7 +15,7 @@
/*
Simulator for the TFMini RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tfmini --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tfmini --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 20

View File

@ -15,7 +15,7 @@
/*
Simulator for the GY-US42-v2 serial rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:gyus42v2 --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:gyus42v2 --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 31

View File

@ -15,7 +15,7 @@
/*
Simulator for the JAE JRE radio altimiter
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:jre --speedup=1 -L KalaupapaCliffs --map
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:jre --speedup=1 -L KalaupapaCliffs --map
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 38

View File

@ -15,7 +15,7 @@
/*
Simulator for the Lanbao rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lanbao --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lanbao --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 26

View File

@ -15,7 +15,7 @@
/*
Simulator for the LeddarOne rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:leddarone --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:leddarone --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 12

View File

@ -15,7 +15,7 @@
/*
Simulator for the serial LightWare rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 8

View File

@ -15,7 +15,7 @@
/*
Simulator for the serial LightWare rangefinder - binary mode
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial-binary --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial-binary --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 8

View File

@ -15,7 +15,7 @@
/*
Simulator for the NMEA serial rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rf_mavlink --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rf_mavlink --speedup=1
param set SERIAL5_PROTOCOL 1
param set RNGFND1_TYPE 10

View File

@ -15,7 +15,7 @@
/*
Simulator for the MaxsonarSerialLV rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:maxsonarseriallv --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:maxsonarseriallv --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 13

View File

@ -15,7 +15,7 @@
/*
Simulator for the NMEA serial rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:nmea --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:nmea --speedup=1
param set SERIAL5_PROTOCOL 9
param set SERIAL5_BAUD 9600

View File

@ -15,7 +15,7 @@
/*
Simulator for the RDS02UF rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rds02uf --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rds02uf --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 36

View File

@ -12,7 +12,7 @@
*/
/*
Simulator for the TeraRanger NEO RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:teraranger_serial --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:teraranger_serial --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 35
graph RANGEFINDER.distance

View File

@ -15,7 +15,7 @@
/*
Simulator for the USD1 v0 Serial RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v0 --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v0 --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 11

View File

@ -15,7 +15,7 @@
/*
Simulator for the USD1 v1 Serial RangeFinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v1 --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v1 --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 11

View File

@ -15,7 +15,7 @@
/*
Simulator for the Wasp serial rangefinder
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:wasp --speedup=1
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:wasp --speedup=1
param set SERIAL5_PROTOCOL 9
param set RNGFND1_TYPE 18

View File

@ -15,7 +15,7 @@
/*
Simulator for the RichenPower Hybrid generators
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:richenpower --speedup=1 --console
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:richenpower --speedup=1 --console
param set SERIAL5_PROTOCOL 30
param set SERIAL5_BAUD 9600

View File

@ -20,7 +20,7 @@
AHRS_EKF_TYPE = 11
EAHRS_TYPE=1
sim_vehicle.py -D --console --map -A --uartF=sim:VectorNav
sim_vehicle.py -D --console --map -A --serial5=sim:VectorNav
*/
#pragma once

View File

@ -46,7 +46,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools
}
# start up main copter in the current directory
$COPTER --model airsim-copter --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS &
$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS &
# Set number of extra copters to be simulated, change this for increasing the count
NCOPTERS="1"
@ -71,7 +71,7 @@ FOLL_SYSID $FOLL_SYSID
FOLL_DIST_MAX 1000
EOF
pushd copter$i
$COPTER --model airsim-copter --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm &
$COPTER --model airsim-copter --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm &
popd
done
wait

View File

@ -28,7 +28,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools
}
# start up main copter in the current directory
$COPTER --model airsim-copter --uartA udpclient:$GCS_IP:14550 --uartB tcp:0 --defaults $BASE_DEFAULTS &
$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14550 --serial3 tcp:0 --defaults $BASE_DEFAULTS &
# Set number of "extra" copters to be simulated, change this for increasing the count
NCOPTERS="1"
@ -49,7 +49,7 @@ SYSID_THISMAV $SYSID
EOF
pushd copter$i
$COPTER --model airsim-copter --uartA udpclient:$GCS_IP:$UDP_PORT --uartB tcp:$i \
$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:$UDP_PORT --serial3 tcp:$i \
--instance $i --defaults $BASE_DEFAULTS,identity.parm &
popd
done

View File

@ -13,14 +13,14 @@ PLANE=$ROOTDIR/build/sitl/bin/arduplane
}
# setup for either TCP or multicast
#UARTA="tcp:0"
UARTA="mcast:"
#SERIAL0="tcp:0"
SERIAL0="mcast:"
PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane.parm"
COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm"
mkdir -p swarm/plane swarm/copter
(cd swarm/plane && $PLANE --model plane --uartA $UARTA --defaults $PLANE_DEFAULTS) &
(cd swarm/plane && $PLANE --model plane --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) &
# create default parameter file for the follower
cat <<EOF > swarm/copter/follow.parm
@ -32,5 +32,5 @@ FOLL_SYSID 1
FOLL_DIST_MAX 1000
EOF
(cd swarm/copter && $COPTER --model quad --uartA $UARTA --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) &
(cd swarm/copter && $COPTER --model quad --serial0 $SERIAL0 --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) &
wait

View File

@ -9,7 +9,7 @@ GCS_IP=192.168.2.48
BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/rover.parm,$ROOTDIR/Tools/autotest/default_params/rover-skid.parm"
# start up main rover in the current directory
$ROVER --model morse-skid --uartA udpclient:$GCS_IP --uartC mcast: --defaults $BASE_DEFAULTS &
$ROVER --model morse-skid --serial0 udpclient:$GCS_IP --serial1 mcast: --defaults $BASE_DEFAULTS &
# now start 2 rovers to follow the first, using
# a separate directory for each to keep the eeprom.bin
@ -37,7 +37,7 @@ FOLL_SYSID $FOLL_SYSID
FOLL_DIST_MAX 1000
EOF
pushd rov$i
$ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --uartA tcp:0 --uartC mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm &
$ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --serial0 tcp:0 --serial1 mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm &
popd
done
wait

View File

@ -75,7 +75,7 @@ AUTO_OPTIONS 7
EOF
pushd copter1
$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm &
$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm &
popd
# now start other copters to follow the first, using
@ -103,7 +103,7 @@ EOF
pushd copter$i
LAT=$(echo "$HOMELAT + 0.0005*$i" | bc -l)
LONG=$(echo "$HOMELONG + 0.0005*$i" | bc -l)
$COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm &
$COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm &
popd
done
wait