Skip to content

Commit

Permalink
FEATURE: Added Gazebo Iris Model with gimbal
Browse files Browse the repository at this point in the history
Thanks to khanasif786 Asif Khan
  • Loading branch information
amilcarlucas committed Oct 30, 2024
1 parent b7a79ac commit 978497b
Show file tree
Hide file tree
Showing 53 changed files with 2,253 additions and 0 deletions.
1,484 changes: 1,484 additions & 0 deletions vehicle_templates/ArduCopter/GazeboIrisWithTargetFollow/00_default.param

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
INS_LOG_BAT_MASK,3 # the Matek H743 fligth controller only has two IMUs
INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next start
INS_TCAL1_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg
INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next start
INS_TCAL2_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg
LOG_BITMASK,524416 # Only for IMU and Raw-IMU
LOG_DISARMED,1 # Gather data for the offline IMU temperature calibration while the FC is disarmed
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
INS_TCAL1_ACC1_X,115.946591
INS_TCAL1_ACC1_Y,498.256973
INS_TCAL1_ACC1_Z,-381.446152
INS_TCAL1_ACC2_X,-22.931569
INS_TCAL1_ACC2_Y,13.578689
INS_TCAL1_ACC2_Z,19.36129
INS_TCAL1_ACC3_X,-0.601406
INS_TCAL1_ACC3_Y,0.213799
INS_TCAL1_ACC3_Z,0.011622
INS_TCAL1_ENABLE,0
INS_TCAL1_GYR1_X,-32.634221
INS_TCAL1_GYR1_Y,79.655005
INS_TCAL1_GYR1_Z,-151.124203
INS_TCAL1_GYR2_X,-0.611429
INS_TCAL1_GYR2_Y,-2.040989
INS_TCAL1_GYR2_Z,1.23833
INS_TCAL1_GYR3_X,-0.009728
INS_TCAL1_GYR3_Y,0.019492
INS_TCAL1_GYR3_Z,0.00141
INS_TCAL1_TMAX,56
INS_TCAL1_TMIN,-14.6
INS_TCAL2_ACC1_X,-1088.4156
INS_TCAL2_ACC1_Y,806.840522
INS_TCAL2_ACC1_Z,327.521202
INS_TCAL2_ACC2_X,-13.630366
INS_TCAL2_ACC2_Y,6.347961
INS_TCAL2_ACC2_Z,9.967253
INS_TCAL2_ACC3_X,-0.376738
INS_TCAL2_ACC3_Y,0.002642
INS_TCAL2_ACC3_Z,-0.065861
INS_TCAL2_ENABLE,0
INS_TCAL2_GYR1_X,-44.455146
INS_TCAL2_GYR1_Y,-8.833006
INS_TCAL2_GYR1_Z,88.004539
INS_TCAL2_GYR2_X,1.435061
INS_TCAL2_GYR2_Y,-0.204453
INS_TCAL2_GYR2_Z,-2.086232
INS_TCAL2_GYR3_X,-0.048141
INS_TCAL2_GYR3_Y,-0.002373
INS_TCAL2_GYR3_Z,-0.028351
INS_TCAL2_TMAX,56.5
INS_TCAL2_TMIN,-13.3
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
AHRS_ORIENTATION,0 # Point forward in the direction of travel
LOG_DISARMED,0 # Log disarmed was only required for offline IMU temperature calibration
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
ARMING_RUDDER,2 # We find it safer to use only a switch to arm instead of through rudder inputs
BRD_ALT_CONFIG,0
RC_OPTIONS,32 # Enables Crossfire Telemetry
RC_PROTOCOLS,1 # Selected in the component editor
RC6_OPTION,212
RC7_OPTION,213
RC8_OPTION,214
RC9_OPTION,0
RSSI_TYPE,0
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
BRD_SER1_RTSCTS,1 # we have RTS/CTS pins connected
SERIAL1_BAUD,57 # The MAVLink over ESP32 telemetry
SERIAL1_PROTOCOL,2 # Use MAVLink 2 for telemetry
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
ATC_RAT_PIT_SMAX,0 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
ATC_RAT_RLL_SMAX,0 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
ATC_RAT_YAW_SMAX,0 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
MOT_HOVER_LEARN,2 # So that it can tune the throttle controller on 20_throttle_controller.param file
MOT_PWM_MAX,2000
MOT_PWM_MIN,1000
MOT_PWM_TYPE,0 # Specified in component editor window
MOT_SPOOL_TIME,0.5 # left at default because copter is small
NTF_BUZZ_TYPES,5 # the 4-in-1 ESC uses this
NTF_LED_TYPES,123079 # Built-in LED, NCP5623 External (Holybro F9P), Neopixel (Matek H743 slim v3), and DShot (4-in-1 ESC)
PSC_ACCZ_SMAX,0 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
SERIAL5_BAUD,57 # bi-directional DShot telemetry data rate from T-Motor F45 4in1 ESC V2
SERIAL5_PROTOCOL,-1 # bi-directional DShot telemetry pin is connected to SERIAL5
SERVO_BLH_AUTO,1 # Enables BLHeli pass-thru
SERVO_BLH_BDMASK,15 # All four of our ESC support bi-directional DShot
SERVO_BLH_POLES,3 # Specified in component editor window
SERVO_BLH_TRATE,5 # Set to a low value because the RPM telemetry uses bi-directional DShot telemetry instead of this UART telemetry
SERVO_DSHOT_ESC,0 # BLHeli32
SERVO_DSHOT_RATE,0 # Sends DShot control signals to the ESC twice per control loop
SERVO1_MAX,1900 # Use the full available 1000-2000 DShot range
SERVO1_MIN,1100 # Use the full available 1000-2000 DShot range
SERVO1_TRIM,1500 # Use the full available 1000-2000 DShot range
SERVO13_FUNCTION,0 # For matek H743Slim v3 board
SERVO2_MAX,1900 # Use the full available 1000-2000 DShot range
SERVO2_MIN,1100 # Use the full available 1000-2000 DShot range
SERVO2_TRIM,1500 # Use the full available 1000-2000 DShot range
SERVO3_MAX,1900 # Use the full available 1000-2000 DShot range
SERVO3_MIN,1100 # Use the full available 1000-2000 DShot range
SERVO3_TRIM,1500 # Use the full available 1000-2000 DShot range
SERVO4_MAX,1900 # Use the full available 1000-2000 DShot range
SERVO4_MIN,1100 # Use the full available 1000-2000 DShot range
SERVO4_TRIM,1500 # Use the full available 1000-2000 DShot range
TKOFF_RPM_MIN,0 # Our motors should idle at around 1400 RPM, see https://ardupilot.org/copter/docs/tkoff-rpm-min.html
TKOFF_SLEW_TIME,2 # left at default because copter is small
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
BATT_AMP_PERVLT,17 # new calibrated value for Mamba F45_128k 4in1 ESC
BATT_ARM_VOLT,15.7 # Don’t allow arming below this voltage
BATT_CAPACITY,1800 # Total battery capacity specified in the component editor
BATT_CRT_MAH,0 # When only 450mAh out of the total 1800mAh remain, trigger critical failsafe
BATT_CRT_VOLT,14.2 # (Critical voltage + 0.0) x no. of cells
BATT_FS_CRT_ACT,1 # Land ASAP
BATT_FS_LOW_ACT,2 # Return and land at home or rally point
BATT_FS_VOLTSRC,0 # Let the firmware handle the nasty business of variable and battery dependent internal resistance
BATT_LOW_MAH,0 # When only 450mAh out of the total 1800mAh remain, trigger low failsafe
BATT_LOW_VOLT,14.4 # (Low voltage + 0.0) x no. of cells
BATT_MONITOR,4 # Selected in component editor window
BATT_VOLT_MULT,10.1 # Use a power source with a voltage close to BATT_LOW_VOLT measure with a calibrated voltimeter and adapt this parameter so that the telemetry voltage reading matches it
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
BATT2_AMP_PERVLT,17.73 # calibrated using batt charger
BATT2_ARM_VOLT,15 # In our build this is a redundant monitor for batt1 so == BATT_ARM_VOLT
BATT2_CAPACITY,1800 # In our build this is a redundant monitor for batt1 so == BATT_CAPACITY
BATT2_CRT_MAH,450 # In our build this is a redundant monitor for batt1 so == BATT_CRT_MAH
BATT2_CRT_VOLT,14 # In our build this is a redundant monitor for batt1 so == BATT_CRT_VOLT
BATT2_CURR_PIN,7
BATT2_FS_CRT_ACT,1 # flying indoors, just land ASAP, no need to hit the ceiling while doing RTL
BATT2_FS_LOW_ACT,1 # flying indoors, just land ASAP, no need to hit the ceiling while doing RTL
BATT2_FS_VOLTSRC,1 # In our build this is a redundant monitor for batt1 so == BATT_FS_VOLTSRC
BATT2_LOW_MAH,600 # In our build this is a redundant monitor for batt1 so == BATT_LOW_MAH
BATT2_LOW_VOLT,14.4 # In our build this is a redundant monitor for batt1 so == BATT_LOW_VOLT
BATT2_MONITOR,0
BATT2_VOLT_MULT,228.342 # Use a power source with a voltage close to BATT2_LOW_VOLT measure with a calibrated voltimeter and adapt this parameter so that the telemetry voltage reading matches it
BATT2_VOLT_PIN,18
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
BRD_SAFETY_DEFLT,0 # Matek H743 Slim has no safety switch
GPS_GNSS_MODE,7 # limit the constalations to ensure an update rate higher than 5Hz
GPS_POS1_X,0.056 # HX-CH7604A GNSS antenna pahse center location relative to CG
GPS_POS1_Y,0 # HX-CH7604A GNSS antenna pahse center location relative to CG
GPS_POS1_Z,-0.07 # HX-CH7604A GNSS antenna pahse center location relative to CG
GPS_TYPE,2 # Defined in component editor
SERIAL3_PROTOCOL,5 # GNSS receiver is connected to serial3
WPNAV_RADIUS,200 # we have a good GNSS receiver so we can afford to fly precisely
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
ATC_ACCEL_P_MAX,193500 # Derived from vehicle component editor propeller size
ATC_ACCEL_R_MAX,193500 # Derived from vehicle component editor propeller size
ATC_ACCEL_Y_MAX,33300 # Derived from vehicle component editor propeller size
ATC_ANG_YAW_P,5.5 # Derived from vehicle component editor propeller size
ATC_RAT_PIT_FLTD,57.5 # INS_GYRO_FILTER / 2
ATC_RAT_PIT_FLTE,0 # Initial value, will be improved at a later step
ATC_RAT_PIT_FLTT,57.5 # INS_GYRO_FILTER / 2
ATC_RAT_RLL_FLTD,57.5 # INS_GYRO_FILTER / 2
ATC_RAT_RLL_FLTE,0 # Initial value, will be improved at a later step
ATC_RAT_RLL_FLTT,57.5 # INS_GYRO_FILTER / 2
ATC_RAT_YAW_FLTD,0 # Initial value, will be improved at a later step
ATC_RAT_YAW_FLTE,2 # Initial value, will be improved at a later step
ATC_RAT_YAW_FLTT,57.5 # INS_GYRO_FILTER / 2
ATC_THR_MIX_MAN,0.1 # Value for the first couple of flights will be changed later once MOT_THST_HOVER is learned
INS_ACCEL_FILTER,10 # The default is 20Hz but that is too high in most situations
INS_GYRO_FILTER,115 # Derived from vehicle component editor propeller size
MOT_THST_EXPO,0.41 # Derived from vehicle component editor propeller size
MOT_THST_HOVER,0.2 # Hover learn will improve this initial guess
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
AHRS_TRIM_X,0
AHRS_TRIM_Y,0
ATC_ACCEL_P_MAX,110000
ATC_ACCEL_R_MAX,110000
ATC_ACCEL_Y_MAX,27000
ATC_RAT_PIT_FLTD,20 # INS_GYRO_FILTER / 2
ATC_RAT_PIT_FLTT,20 # INS_GYRO_FILTER / 2
ATC_RAT_RLL_FLTD,20 # INS_GYRO_FILTER / 2
ATC_RAT_RLL_FLTT,20 # INS_GYRO_FILTER / 2
ATC_RAT_YAW_FLTE,2.5
ATC_RAT_YAW_FLTT,20 # INS_GYRO_FILTER / 2
COMPASS_EXTERNAL,1
COMPASS_ORIENT,0
COMPASS_PRIO1_ID,97539
COMPASS_USE2,1
COMPASS_USE3,1
FENCE_ACTION,1
FENCE_ALT_MAX,100
FENCE_ENABLE,0
FENCE_RADIUS,150
FLTMODE1,7
FLTMODE2,9
FLTMODE3,6
FLTMODE4,3
FLTMODE5,5
FLTMODE6,0
FRAME_CLASS,1
FRAME_TYPE,1
INS_ACC1_CALTEMP,-300
INS_ACC2_CALTEMP,-300
INS_ACC2SCAL_X,1.001
INS_ACC2SCAL_Y,1.001
INS_ACC2SCAL_Z,1.001
INS_ACC3SCAL_X,1
INS_ACC3SCAL_Y,1
INS_ACC3SCAL_Z,1
INS_ACCSCAL_X,1.001
INS_ACCSCAL_Y,1.001
INS_ACCSCAL_Z,1.001
INS_GYRO_FILTER,20
INS_USE3,1
MOT_BAT_VOLT_MAX,12.8
MOT_BAT_VOLT_MIN,9.6
MOT_SPIN_ARM,0.1
MOT_SPIN_MAX,0.95
MOT_SPIN_MIN,0.15
MOT_THST_EXPO,0.65
MOT_THST_HOVER,0.333855
RC1_MAX,2000
RC1_MIN,1000
RC1_TRIM,1500
RC2_MAX,2000
RC2_MIN,1000
RC2_TRIM,1500
RC3_MAX,2000
RC3_MIN,1000
RC3_TRIM,1500
RC4_MAX,2000
RC4_MIN,1000
RC4_TRIM,1500
RC5_MAX,2000
RC5_MIN,1000
RC5_TRIM,1500
RC6_MAX,1900
RC6_MIN,1100
RC6_TRIM,1500
RC7_MAX,1900
RC7_MIN,1100
RC7_TRIM,1500
RC8_MAX,1900
RC8_MIN,1100
RC8_TRIM,1500
RC9_MAX,1900
RC9_MIN,1100
RC9_TRIM,1500
SERVO1_FUNCTION,33
SERVO2_FUNCTION,34
SERVO3_FUNCTION,35
SERVO4_FUNCTION,36
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
ARMING_CHECK,1 # Perform all arming checks. If you have a problem fix its source. Do NOT change this
BRD_RTC_TZ_MIN,0 # Berlin time zone
CAM1_TRK_COMPID,0
CAM1_TRK_ENABLE,1
CAM1_TRK_SYSID,245
CAM1_TYPE,1
FENCE_TYPE,7 # cylinder and max altitude, to obey local regulations and safety measures
FOLL_DIST_MAX,100
FOLL_ENABLE,1
FOLL_OPTIONS,2
FOLL_POS_P,0.1
FOLL_YAW_BEHAVE,1
INS_ACCEL_FILTER,20 # the default is 20 and that lets too much noise in
INS_POS1_X,0 # was -0.005
INS_POS1_Y,0 # was -0.011
INS_POS2_X,0 # was -0.011
INS_POS2_Y,0 # was -0.01
LAND_ALT_LOW,1000 # come down fast and only slow down close to the ground. We have a good GNSS receiver, so thrust it
NET_ENABLE,1
NET_OPTIONS,0
NET_P1_IP0,127
NET_P1_IP1,0
NET_P1_IP2,0
NET_P1_IP3,1
NET_P1_PORT,14560
NET_P1_TYPE,1
NET_P2_IP0,127
NET_P2_IP1,0
NET_P2_IP2,0
NET_P2_IP3,1
NET_P2_PORT,14570
NET_P2_PROTOCOL,2
NET_P2_TYPE,1
RTL_ALT,1500 # The default is too high for the kind of flights we do. This reduces the altitude for indoors
RTL_LOIT_TIME,5000 # The default is too long. This reduces the time
SCHED_LOOP_RATE,400 # On our vehicle the propellers rotate at speeds higher than 400Hz and we have a powerful STM32 H7 family processor. So we increase this for added performance.
SCR_ENABLE,1 # Use lua scripting for VTOL-Quicktune, MagFit automation and Windspeed Estimation automation
SERVO10_FUNCTION,7
SERVO11_FUNCTION,6
SERVO9_FUNCTION,8
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
INS_LOG_BAT_MASK,0 # The Matek H743 Slim flight controller only has two IMUs
INS_LOG_BAT_OPT,4 # Logs measured data both before and after the filters for Filter Review Webtool usage
INS_RAW_LOG_OPT,0 # To get more Notch filter data
LOG_BITMASK,2242524 # Logs Notch filter data and other control signals
LOG_FILE_DSRMROT,1 # One .bin log file per flight, not per battery/reboot
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
MOT_SPIN_ARM,0.1 # The Mamba F45_128K ESCs reliably start spinning with this value
MOT_SPIN_MAX,0.95 # Upper dead zone of the Mamba F45_128K ESC
MOT_SPIN_MIN,0.15 # MOT_SPIN_ARM + 0.03
MOT_THST_EXPO,0.65 # Measured with the motor test stand RCBenchmark Series 1780 from Tyto Robotics
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
ATC_INPUT_TC,0.15
ATC_RAT_PIT_D,0.0036 # = 0.925972 * (0.0036 default)
ATC_RAT_PIT_I,0.135 # = 1.283176 * (0.135 default)
ATC_RAT_PIT_P,0.135 # = 1.283176 * (0.135 default)
ATC_RAT_RLL_D,0.0036 # = 0.690593 * (0.0036 default)
ATC_RAT_RLL_I,0.135 # = 1.061015 * (0.135 default)
ATC_RAT_RLL_P,0.135 # = 1.061015 * (0.135 default)
ATC_RAT_YAW_D,0 # = 1 * (0 default)
ATC_RAT_YAW_I,0.02 # = 2.514026 * (0.018 default)
ATC_RAT_YAW_P,0.3 # = 2.514026 * (0.18 default)
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
DID_CANDRIVER,0
DID_ENABLE,0 # Our RemoteID module does not communicate with ArduPilot
DID_MAVPORT,2 # The serial port attached to the OpenDroneID module
DID_OPTIONS,0
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
INS_FAST_SAMPLE,1 # Both IMUs can run fast on the Matek H743 Slim flight controller
INS_GYRO_RATE,0 # the H743 can do 4KHz here
INS_HNTCH_ATT,20 # this is just a hunch, it must be improved after the first flight (by the next file)
INS_HNTCH_BW,20 # this is just a hunch, it must be improved after the first flight (by the next file)
INS_HNTCH_ENABLE,1 # Use the first notch filter to filter the noise created by the motors/propellers
INS_HNTCH_FREQ,161 # Use 1.4 * INS_GYRO_FILTER as a first guess
INS_HNTCH_HMNCS,1 # start with a single frequency
INS_HNTCH_MODE,3 # Use the BDshot600 RPM telemetry to dynamicaly track noise created by the motors/propellers
INS_HNTCH_OPTS,6 # One Notch per motor, update at loop rate
INS_HNTCH_REF,1 # Use the BDshot600 RPM telemetry to dynamicaly track noise created by the motors/propellers
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
INS_HNTCH_ATT,30 # just enough to filter the noise created by the motors/propellers
INS_HNTCH_BW,30 # just enough to filter the noise created by the motors/propellers
INS_HNTCH_FM_RAT,1 # Allowed undercutting of the base frequency of the first notch filter
INS_HNTCH_FREQ,115 # the minimum frequency that the motors are expected to operate at
INS_HNTCH_HMNCS,3 # the motors produce secondary harmonics on this vehicle
INS_HNTCH_OPTS,6 # One Notch per motor, update at loop rate
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ATC_THR_MIX_MAN,0.1 # because we have learned the MOT_THST_HOVER value
PSC_ACCZ_I,1 # Use 2 * MOT_THST_HOVER assuming MOT_THST_HOVER has been correctly learned
PSC_ACCZ_P,0.5 # Use MOT_THST_HOVER assuming MOT_THST_HOVER has been correctly learned
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
EK3_ACC_P_NSE,0.35 # higher value -> trust accelerometer less, compared to other sources
EK3_ALT_M_NSE,2 # lower value -> trust baro more, compared to other sources
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
QUIK_AUTO_FILTER,1
QUIK_AUTO_SAVE,0
QUIK_AXES,7
QUIK_DOUBLE_TIME,10
QUIK_ENABLE,1 # Use VTOL-Quicktune lua script to estimate a good PID starting values
QUIK_GAIN_MARGIN,60
QUIK_MAX_REDUCE,20
QUIK_OPTIONS,0
QUIK_OSC_SMAX,5
QUIK_RC_FUNC,300 # the script uses this value to listen to RC switch
QUIK_RP_PI_RATIO,1
QUIK_Y_PI_RATIO,10
QUIK_YAW_D_MAX,0.01
QUIK_YAW_P_MAX,0.5
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
ATC_RAT_PIT_D,0.0036 # Tuned in a Hangar
ATC_RAT_PIT_I,0.135 # Tuned in a Hangar
ATC_RAT_PIT_P,0.135 # Tuned in a Hangar
ATC_RAT_RLL_D,0.0036 # Tuned in a Hangar
ATC_RAT_RLL_I,0.135 # Tuned in a Hangar
ATC_RAT_RLL_P,0.135 # Tuned in a Hangar
ATC_RAT_YAW_D,0 # Tuned in a Hangar
ATC_RAT_YAW_FLTD,20 # Tuned in a Hangar
ATC_RAT_YAW_I,0.02 # Tuned in a Hangar
ATC_RAT_YAW_P,0.3 # Tuned in a Hangar
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
MAGH_ALT_DELTA,10 # Height difference between the highest and lowest point of the eight
MAGH_B,1.2 # Geometric factor for the width of the eight
MAGH_CMD,117 # Script_Time command value for identification of the script
MAGH_COUNT,6 # Number of times the drone repeats the eight
MAGH_LOG_ENABLE,1 # Activates the logging of the MAGH.Active message
MAGH_MIN_SPEED,5 # Starting speed for the mission; slowly adjusts to the general speed in auto-missions
MAGH_NUM_WP,18 # Number of waypoints from which the eight is built
MAGH_USE_LOITER,0 # Sets a Loiter_unlimited command at the beginning of the mission to check the generated waypoints
Loading

0 comments on commit 978497b

Please sign in to comment.