mirror of https://github.com/ArduPilot/ardupilot
Tools: rename GPS_ to GPS1_
This commit is contained in:
parent
94d5d92917
commit
0e4b41baa6
|
@ -22,7 +22,7 @@ BATT_MONITOR,4
|
|||
BRD_SAFETY_DEFLT,0
|
||||
FRAME_CLASS,1
|
||||
FRAME_TYPE,1
|
||||
GPS_TYPE,2
|
||||
GPS1_TYPE,2
|
||||
INS_GYRO_FILTER,40
|
||||
MOT_BAT_VOLT_MAX,12.6
|
||||
MOT_BAT_VOLT_MIN,9.9
|
||||
|
|
|
@ -8,7 +8,7 @@ BATT_VOLT_PIN,-1
|
|||
CRUISE_SPEED,1.0
|
||||
EK2_ENABLE,0
|
||||
EK3_ENABLE,1
|
||||
GPS_TYPE,2
|
||||
GPS1_TYPE,2
|
||||
MIS_RESTART,1
|
||||
MODE_CH,5
|
||||
MODE1,10
|
||||
|
|
|
@ -2680,7 +2680,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
'''fly mission which tests normal operation alongside CAN GPS'''
|
||||
self.set_parameters({
|
||||
"CAN_P1_DRIVER": 1,
|
||||
"GPS_TYPE": 9,
|
||||
"GPS1_TYPE": 9,
|
||||
"GPS2_TYPE": 9,
|
||||
# disable simulated GPS, so only via DroneCAN
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
|
@ -2729,7 +2729,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
for case in GPS_Order_Tests:
|
||||
self.progress("############################### Trying Case: " + str(case))
|
||||
self.set_parameters({
|
||||
"GPS_CAN_OVRIDE": case[0],
|
||||
"GPS1_CAN_OVRIDE": case[0],
|
||||
"GPS2_CAN_OVRIDE": case[1],
|
||||
})
|
||||
self.drain_mav()
|
||||
|
@ -3137,7 +3137,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"EK3_SRC1_VELZ": 6,
|
||||
})
|
||||
self.set_parameters({
|
||||
"GPS_TYPE": 0,
|
||||
"GPS1_TYPE": 0,
|
||||
"VISO_TYPE": 1,
|
||||
"SERIAL5_PROTOCOL": 1,
|
||||
})
|
||||
|
@ -3233,7 +3233,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"EK3_SRC1_VELXY": 6,
|
||||
"EK3_SRC1_POSZ": 6,
|
||||
"EK3_SRC1_VELZ": 6,
|
||||
"GPS_TYPE": 0,
|
||||
"GPS1_TYPE": 0,
|
||||
"VISO_TYPE": 1,
|
||||
"SERIAL5_PROTOCOL": 1,
|
||||
"SIM_VICON_TMASK": 8, # send VISION_POSITION_DELTA
|
||||
|
@ -3410,7 +3410,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
|
||||
# switch to vicon, disable GPS and wait 10sec to ensure vehicle remains in Loiter
|
||||
self.set_rc(8, 1500)
|
||||
self.set_parameter("GPS_TYPE", 0)
|
||||
self.set_parameter("GPS1_TYPE", 0)
|
||||
|
||||
# ensure vehicle remain in Loiter for 15 seconds
|
||||
tstart = self.get_sim_time()
|
||||
|
@ -6935,7 +6935,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Ensure we can't enter LOITER without position")
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"GPS_TYPE": 2,
|
||||
"GPS1_TYPE": 2,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
})
|
||||
# if there is no GPS at all then we must direct EK3 to not use
|
||||
|
@ -7469,7 +7469,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"BCN_ALT": SITL_START_LOCATION.alt,
|
||||
"BCN_ORIENT_YAW": 0,
|
||||
"AVOID_ENABLE": 4,
|
||||
"GPS_TYPE": 0,
|
||||
"GPS1_TYPE": 0,
|
||||
"EK3_ENABLE": 1,
|
||||
"EK3_SRC1_POSXY": 4, # Beacon
|
||||
"EK3_SRC1_POSZ": 1, # Baro
|
||||
|
@ -8641,9 +8641,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"AHRS_TRIM_X": 0.01,
|
||||
"AHRS_TRIM_Y": -0.03,
|
||||
"GPS2_TYPE": 1,
|
||||
"GPS_POS_X": 0.1,
|
||||
"GPS_POS_Y": 0.2,
|
||||
"GPS_POS_Z": 0.3,
|
||||
"GPS1_POS_X": 0.1,
|
||||
"GPS1_POS_Y": 0.2,
|
||||
"GPS1_POS_Z": 0.3,
|
||||
"GPS2_POS_X": -0.1,
|
||||
"GPS2_POS_Y": -0.02,
|
||||
"GPS2_POS_Z": -0.31,
|
||||
|
@ -9010,7 +9010,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("fly 50m North (or whatever)")
|
||||
old_pos = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
self.fly_guided_move_global_relative_alt(50, 0, 20)
|
||||
self.set_parameter('GPS_TYPE', 0)
|
||||
self.set_parameter('GPS1_TYPE', 0)
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
|
@ -9289,7 +9289,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("fly 50m North (or whatever)")
|
||||
old_pos = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
self.fly_guided_move_global_relative_alt(50, 0, 50)
|
||||
self.set_parameter('GPS_TYPE', 0)
|
||||
self.set_parameter('GPS1_TYPE', 0)
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
|
@ -9301,7 +9301,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Distance: %f" % pos_delta)
|
||||
if pos_delta < 5:
|
||||
raise NotAchievedException("Bug reproduced - returned to near origin")
|
||||
self.set_parameter('GPS_TYPE', 1)
|
||||
self.set_parameter('GPS1_TYPE', 1)
|
||||
self.do_RTL()
|
||||
|
||||
def GPSForYaw(self):
|
||||
|
|
|
@ -3176,7 +3176,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
"EAHRS_TYPE": eahrs_type,
|
||||
"SERIAL4_PROTOCOL": 36,
|
||||
"SERIAL4_BAUD": 230400,
|
||||
"GPS_TYPE": 21,
|
||||
"GPS1_TYPE": 21,
|
||||
"AHRS_EKF_TYPE": 11,
|
||||
"INS_GYR_CAL": 1,
|
||||
})
|
||||
|
|
|
@ -2,4 +2,4 @@ BCN_TYPE 10
|
|||
BCN_ALT 584.900024
|
||||
BCN_LATITUDE -35.363262
|
||||
BCN_LONGITUDE 149.165237
|
||||
GPS_TYPE 0
|
||||
GPS1_TYPE 0
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
# SITL GPS-for-yaw using a single simulated NMEA GPS
|
||||
EK3_SRC1_YAW 2
|
||||
GPS_TYPE 5
|
||||
GPS1_TYPE 5
|
||||
SIM_GPS_TYPE 5
|
||||
SIM_GPS_HDG 1
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
# SITL GPS-for-yaw using two simulated UBlox GPSs
|
||||
EK3_SRC1_YAW 2
|
||||
GPS_AUTO_CONFIG 0
|
||||
GPS_TYPE 17
|
||||
GPS1_TYPE 17
|
||||
GPS2_TYPE 18
|
||||
GPS_POS_Y -0.2
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# parameters for SITL peripheral
|
||||
|
||||
GPS_TYPE 1
|
||||
GPS1_TYPE 1
|
||||
COMPASS_ENABLE 1
|
||||
BARO_ENABLE 1
|
||||
ARSPD_TYPE 100
|
||||
|
|
|
@ -2,7 +2,7 @@ CAN_P1_DRIVER 1
|
|||
CAN_D1_UC_ESC_BM 0x0F
|
||||
SIM_CAN_SRV_MSK 0xFf
|
||||
SIM_VIB_MOT_MAX 270
|
||||
GPS_TYPE 9
|
||||
GPS1_TYPE 9
|
||||
RNGFND1_TYPE 24
|
||||
RNGFND1_MAX_CM 11000
|
||||
BATT_MONITOR 8
|
||||
|
|
|
@ -5,7 +5,7 @@ CAN_D1_UC_SRV_BM 0x0F
|
|||
CAN_D1_UC_OPTION 16
|
||||
SIM_CAN_SRV_MSK 0xfff
|
||||
SIM_VIB_MOT_MAX 270
|
||||
GPS_TYPE 9
|
||||
GPS1_TYPE 9
|
||||
ARSPD_TYPE 8
|
||||
RNGFND1_TYPE 24
|
||||
RNGFND1_MAX_CM 11000
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
# SITL GPS-for-yaw using two simulated UBlox GPSs
|
||||
EK3_SRC1_YAW 2
|
||||
GPS_AUTO_CONFIG 0
|
||||
GPS_TYPE 17
|
||||
GPS1_TYPE 17
|
||||
GPS2_TYPE 18
|
||||
GPS_POS_Y -0.2
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
|
|
|
@ -224,14 +224,14 @@ GPS_BLEND_MASK,5
|
|||
GPS_BLEND_TC,10
|
||||
GPS_DELAY_MS,0
|
||||
GPS_DELAY_MS2,0
|
||||
GPS_GNSS_MODE,0
|
||||
GPS1_GNSS_MODE,0
|
||||
GPS2_GNSS_MODE,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS_X,0
|
||||
GPS_POS_Y,0
|
||||
GPS_POS_Z,0
|
||||
GPS1_POS_X,0
|
||||
GPS1_POS_Y,0
|
||||
GPS1_POS_Z,0
|
||||
GPS2_POS_X,0
|
||||
GPS2_POS_Y,0
|
||||
GPS2_POS_Z,0
|
||||
|
@ -241,7 +241,7 @@ GPS_RAW_DATA,0
|
|||
GPS_SAVE_CFG,0
|
||||
GPS_SBAS_MODE,2
|
||||
GPS_SBP_LOGMASK,-32768
|
||||
GPS_TYPE,1
|
||||
GPS1_TYPE,1
|
||||
GPS2_TYPE,0
|
||||
GROUND_STEER_ALT,0
|
||||
GROUND_STEER_DPS,90
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
'''
|
||||
Test parameter upgrade, master vs branch
|
||||
|
||||
./Tools/autotest/test_param_upgrade.py --vehicle=arduplane --param GPS_TYPE=17 --param "GPS_TYPE2=37->GPS2_TYPE=37" --param GPS_GNSS_MODE=21 --param "GPS_GNSS_MODE2=45->GPS2_GNSS_MODE=45" --param GPS_RATE_MS=186 --param "GPS_RATE_MS2=123->GPS2_RATE_MS=123" --param "GPS_POS1_X=3.75->GPS_POS_X=3.75" --param "GPS_POS2_X=6.9->GPS2_POS_X=6.9" --param "GPS_POS1_Y=2.75->GPS_POS_Y=2.75" --param "GPS_POS2_Y=5.9->GPS2_POS_Y=5.9" --param "GPS_POS1_Z=12.1->GPS_POS_Z=12.1" --param "GPS_POS2_Z=-6.9->GPS2_POS_Z=-6.9" --param "GPS_DELAY_MS=987" --param "GPS_DELAY_MS2=2345->GPS2_DELAY_MS=2345" --param "GPS_COM_PORT=19" --param "GPS_COM_PORT2=100->GPS2_COM_PORT=100" --param "GPS_CAN_NODEID1=109->GPS_CAN_NODEID=109" --param "GPS_CAN_NODEID2=102->GPS2_CAN_NODEID=102" --param "GPS1_CAN_OVRIDE=34->GPS_CAN_OVRIDE=34" --param "GPS2_CAN_OVRIDE=67" --param "GPS_MB1_TYPE=1->GPS_MB_TYPE=1" --param "GPS_MB1_OFS_X=3.14->GPS_MB_OFS_X=3.14" --param "GPS_MB1_OFS_Y=2.18->GPS_MB_OFS_Y=2.18" --param "GPS_MB1_OFS_Z=17.6->GPS_MB_OFS_Z=17.6" --param "GPS_MB2_TYPE=13->GPS2_MB_TYPE=13" --param "GPS_MB2_OFS_X=17.14->GPS2_MB_OFS_X=17.14" --param "GPS_MB2_OFS_Y=12.18->GPS2_MB_OFS_Y=12.18" --param "GPS_MB2_OFS_Z=27.6->GPS2_MB_OFS_Z=27.6" # noqa
|
||||
./Tools/autotest/test_param_upgrade.py --vehicle=arduplane --param "GPS_TYPE=17->GPS1_TYPE=17" --param "GPS_TYPE2=37->GPS2_TYPE=37" --param "GPS_GNSS_MODE=21->GPS1_GNSS_MODE=21" --param "GPS_GNSS_MODE2=45->GPS2_GNSS_MODE=45" --param "GPS_RATE_MS=186->GPS1_RATE_MS=186" --param "GPS_RATE_MS2=123->GPS2_RATE_MS=123" --param "GPS_POS1_X=3.75->GPS1_POS_X=3.75" --param "GPS_POS2_X=6.9->GPS2_POS_X=6.9" --param "GPS_POS1_Y=2.75->GPS1_POS_Y=2.75" --param "GPS_POS2_Y=5.9->GPS2_POS_Y=5.9" --param "GPS_POS1_Z=12.1->GPS1_POS_Z=12.1" --param "GPS_POS2_Z=-6.9->GPS2_POS_Z=-6.9" --param "GPS_DELAY_MS=987->GPS1_DELAY_MS=987" --param "GPS_DELAY_MS2=2345->GPS2_DELAY_MS=2345" --param "GPS_COM_PORT=19->GPS1_COM_PORT=19" --param "GPS_COM_PORT2=100->GPS2_COM_PORT=100" --param "GPS_CAN_NODEID1=109->GPS1_CAN_NODEID=109" --param "GPS_CAN_NODEID2=102->GPS2_CAN_NODEID=102" --param "GPS1_CAN_OVRIDE=34->GPS1_CAN_OVRIDE=34" --param "GPS2_CAN_OVRIDE=67" --param "GPS_MB1_TYPE=1->GPS1_MB_TYPE=1" --param "GPS_MB1_OFS_X=3.14->GPS1_MB_OFS_X=3.14" --param "GPS_MB1_OFS_Y=2.18->GPS1_MB_OFS_Y=2.18" --param "GPS_MB1_OFS_Z=17.6->GPS1_MB_OFS_Z=17.6" --param "GPS_MB2_TYPE=13->GPS2_MB_TYPE=13" --param "GPS_MB2_OFS_X=17.14->GPS2_MB_OFS_X=17.14" --param "GPS_MB2_OFS_Y=12.18->GPS2_MB_OFS_Y=12.18" --param "GPS_MB2_OFS_Z=27.6->GPS2_MB_OFS_Z=27.6" # noqa
|
||||
|
||||
AP_FLAKE8_CLEAN
|
||||
'''
|
||||
|
|
|
@ -13633,7 +13633,7 @@ switch value'''
|
|||
self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)
|
||||
if gps_type is None:
|
||||
gps_type = 1 # auto-detect
|
||||
self.set_parameter("GPS_TYPE", gps_type)
|
||||
self.set_parameter("GPS1_TYPE", gps_type)
|
||||
self.context_clear_collection('STATUSTEXT')
|
||||
self.reboot_sitl()
|
||||
if detect_prefix == "probing":
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
AHRS_EKF_TYPE 10
|
||||
|
||||
GPS_TYPE 100
|
||||
GPS1_TYPE 100
|
||||
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
AHRS_EKF_TYPE 10
|
||||
|
||||
GPS_TYPE 100
|
||||
GPS1_TYPE 100
|
||||
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
|
|
Loading…
Reference in New Issue