Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
laozhou-fujian authored Mar 19, 2024
2 parents 83881ba + 463301a commit 7db24ee
Show file tree
Hide file tree
Showing 80 changed files with 2,299 additions and 417 deletions.
1 change: 1 addition & 0 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ void AP_Periph_FW::init()
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
gps.set_default_type_for_gps1(HAL_GPS1_TYPE_DEFAULT);
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
#if HAL_LOGGING_ENABLED
Expand Down
16 changes: 16 additions & 0 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,11 @@ void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,
total_size);
}

// compatability code added Mar 2024 for 4.6:
#ifndef AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
#define AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED 1
#endif

/*
handle parameter GetSet request
*/
Expand All @@ -245,7 +250,18 @@ void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRx
vp = nullptr;
} else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) {
memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);
#if AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
// cope with older versions of ArduPilot attempting to
// auto-configure AP_Periph using "GPS_TYPE" by
// auto-converting to "GPS1_TYPE":
if (strncmp((char*)req.name.data, "GPS_TYPE", req.name.len) == 0) {
vp = AP_Param::find("GPS1_TYPE", &ptype);
} else {
vp = AP_Param::find((char *)pkt.name.data, &ptype);
}
#else
vp = AP_Param::find((char *)pkt.name.data, &ptype);
#endif
} else {
AP_Param::ParamToken token {};
vp = AP_Param::find_by_index(req.index, &ptype, &token);
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/amovlab-p200.param
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/eLAB_VEK_AI_Rover.param
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
38 changes: 19 additions & 19 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -2680,8 +2680,8 @@ def CANGPSCopterMission(self):
'''fly mission which tests normal operation alongside CAN GPS'''
self.set_parameters({
"CAN_P1_DRIVER": 1,
"GPS_TYPE": 9,
"GPS_TYPE2": 9,
"GPS1_TYPE": 9,
"GPS2_TYPE": 9,
# disable simulated GPS, so only via DroneCAN
"SIM_GPS_DISABLE": 1,
"SIM_GPS2_DISABLE": 1,
Expand Down Expand Up @@ -2860,7 +2860,7 @@ def GuidedEKFLaneChange(self):
self.set_parameters({
"EK3_SRC1_POSZ": 3,
"EK3_AFFINITY" : 1,
"GPS_TYPE2" : 1,
"GPS2_TYPE" : 1,
"SIM_GPS2_DISABLE" : 0,
"SIM_GPS2_GLTCH_Z" : -30
})
Expand Down Expand Up @@ -3137,7 +3137,7 @@ def VisionPosition(self):
"EK3_SRC1_VELZ": 6,
})
self.set_parameters({
"GPS_TYPE": 0,
"GPS1_TYPE": 0,
"VISO_TYPE": 1,
"SERIAL5_PROTOCOL": 1,
})
Expand Down Expand Up @@ -3233,7 +3233,7 @@ def BodyFrameOdom(self):
"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
Expand Down Expand Up @@ -3410,7 +3410,7 @@ def GPSViconSwitching(self):

# 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()
Expand Down Expand Up @@ -6935,7 +6935,7 @@ def loiter_requires_position(self):
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
Expand Down Expand Up @@ -7469,7 +7469,7 @@ def BeaconPosition(self):
"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
Expand Down Expand Up @@ -8640,13 +8640,13 @@ def test_replay_gps_bit(self):
"EK2_ENABLE": 1,
"AHRS_TRIM_X": 0.01,
"AHRS_TRIM_Y": -0.03,
"GPS_TYPE2": 1,
"GPS_POS1_X": 0.1,
"GPS_POS1_Y": 0.2,
"GPS_POS1_Z": 0.3,
"GPS_POS2_X": -0.1,
"GPS_POS2_Y": -0.02,
"GPS_POS2_Z": -0.31,
"GPS2_TYPE": 1,
"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,
"INS_POS1_X": 0.12,
"INS_POS1_Y": 0.14,
"INS_POS1_Z": -0.02,
Expand Down Expand Up @@ -8717,7 +8717,7 @@ def GPSBlending(self):
try:
# configure:
self.set_parameters({
"GPS_TYPE2": 1,
"GPS2_TYPE": 1,
"SIM_GPS2_TYPE": 1,
"SIM_GPS2_DISABLE": 0,
"GPS_AUTO_SWITCH": 2,
Expand Down Expand Up @@ -9010,7 +9010,7 @@ def PositionWhenGPSIsZero(self):
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:
Expand Down Expand Up @@ -9289,7 +9289,7 @@ def RefindGPS(self):
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:
Expand All @@ -9301,7 +9301,7 @@ def RefindGPS(self):
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):
Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -3176,7 +3176,7 @@ def fly_external_AHRS(self, sim, eahrs_type, mission):
"EAHRS_TYPE": eahrs_type,
"SERIAL4_PROTOCOL": 36,
"SERIAL4_BAUD": 230400,
"GPS_TYPE": 21,
"GPS1_TYPE": 21,
"AHRS_EKF_TYPE": 11,
"INS_GYR_CAL": 1,
})
Expand Down Expand Up @@ -3486,7 +3486,7 @@ def EKFlaneswitch(self):
"AHRS_EKF_TYPE": 3,
"EK3_AFFINITY": 15, # enable affinity for all sensors
"EK3_IMU_MASK": 3, # use only 2 IMUs
"GPS_TYPE2": 1,
"GPS2_TYPE": 1,
"SIM_GPS2_DISABLE": 0,
"SIM_BARO_COUNT": 2,
"SIM_BAR2_DISABLE": 0,
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/copter-beacon.parm
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/copter-gps-for-yaw-nmea.parm
Original file line number Diff line number Diff line change
@@ -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
8 changes: 4 additions & 4 deletions Tools/autotest/default_params/copter-gps-for-yaw.parm
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
# SITL GPS-for-yaw using two simulated UBlox GPSs
EK3_SRC1_YAW 2
GPS_AUTO_CONFIG 0
GPS_TYPE 17
GPS_TYPE2 18
GPS_POS1_Y -0.2
GPS_POS2_Y 0.2
GPS1_TYPE 17
GPS2_TYPE 18
GPS1_POS_Y -0.2
GPS2_POS_Y 0.2
SIM_GPS_POS_Y -0.2
SIM_GPS2_POS_Y 0.2
SIM_GPS2_DISABLE 0
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/periph.parm
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# parameters for SITL peripheral

GPS_TYPE 1
GPS1_TYPE 1
COMPASS_ENABLE 1
BARO_ENABLE 1
ARSPD_TYPE 100
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/quad-can.parm
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/quadplane-can.parm
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 4 additions & 4 deletions Tools/autotest/default_params/tracker-gps-for-yaw.parm
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
# SITL GPS-for-yaw using two simulated UBlox GPSs
EK3_SRC1_YAW 2
GPS_AUTO_CONFIG 0
GPS_TYPE 17
GPS_TYPE2 18
GPS_POS1_Y -0.2
GPS_POS2_Y 0.2
GPS1_TYPE 17
GPS2_TYPE 18
GPS1_POS_Y -0.2
GPS2_POS_Y 0.2
SIM_GPS_POS_Y -0.2
SIM_GPS2_POS_Y 0.2
SIM_GPS2_DISABLE 0
Expand Down
22 changes: 11 additions & 11 deletions Tools/autotest/default_params/vee-gull_005.param
Original file line number Diff line number Diff line change
Expand Up @@ -224,25 +224,25 @@ GPS_BLEND_MASK,5
GPS_BLEND_TC,10
GPS_DELAY_MS,0
GPS_DELAY_MS2,0
GPS_GNSS_MODE,0
GPS_GNSS_MODE2,0
GPS1_GNSS_MODE,0
GPS2_GNSS_MODE,0
GPS_INJECT_TO,127
GPS_MIN_ELEV,-100
GPS_NAVFILTER,8
GPS_POS1_X,0
GPS_POS1_Y,0
GPS_POS1_Z,0
GPS_POS2_X,0
GPS_POS2_Y,0
GPS_POS2_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
GPS_RATE_MS,200
GPS_RATE_MS2,200
GPS2_RATE_MS,200
GPS_RAW_DATA,0
GPS_SAVE_CFG,0
GPS_SBAS_MODE,2
GPS_SBP_LOGMASK,-32768
GPS_TYPE,1
GPS_TYPE2,0
GPS1_TYPE,1
GPS2_TYPE,0
GROUND_STEER_ALT,0
GROUND_STEER_DPS,90
ICE_ENABLE,0
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/test_param_upgrade.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
'''
Expand Down
10 changes: 5 additions & 5 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -12062,7 +12062,7 @@ def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT"
def NMEAOutput(self):
'''Test AHRS NMEA Output can be read by out NMEA GPS'''
self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output
self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA
self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA
port = self.spare_network_port()
self.customise_SITL_commandline([
"--serial4=tcp:%u" % port, # GPS2 is NMEA....
Expand Down Expand Up @@ -13633,7 +13633,7 @@ def GPSTypes(self):
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":
Expand All @@ -13656,10 +13656,10 @@ def MultipleGPS(self):
'''check ArduPilot behaviour across multiple GPS units'''
self.assert_message_rate_hz('GPS2_RAW', 0)

# we start sending GPS_TYPE2 - but it will never actually be
# we start sending GPS2_TYPE - but it will never actually be
# filled in as _port[1] is only filled in in AP_GPS::init()
self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")
self.set_parameter("GPS_TYPE2", 1)
self.set_parameter("GPS2_TYPE", 1)
self.assert_message_rate_hz('GPS2_RAW', 5)

self.start_subtest("Ensure correct fix type when no connected GPS")
Expand All @@ -13671,7 +13671,7 @@ def MultipleGPS(self):
self.start_subtest("Ensure detection when sim gps connected")
self.set_parameter("SIM_GPS2_TYPE", 1)
self.set_parameter("SIM_GPS2_DISABLE", 0)
# a reboot is required after setting GPS_TYPE2. We start
# a reboot is required after setting GPS2_TYPE. We start
# sending GPS2_RAW out, once the parameter is set, but a
# reboot is required because _port[1] is only set in
# AP_GPS::init() at boot time, so it will never be detected.
Expand Down
Binary file added Tools/bootloaders/JHEM_JHEF405_bl.bin
Binary file not shown.
Loading

0 comments on commit 7db24ee

Please sign in to comment.