Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into pr-fix-qurt-spi-transfer
Browse files Browse the repository at this point in the history
  • Loading branch information
katzfey authored Nov 14, 2024
2 parents bbef76f + f07df39 commit b11c723
Show file tree
Hide file tree
Showing 6 changed files with 1,282 additions and 20 deletions.
424 changes: 424 additions & 0 deletions AntennaTracker/ReleaseNotes.txt

Large diffs are not rendered by default.

424 changes: 424 additions & 0 deletions ArduCopter/ReleaseNotes.txt

Large diffs are not rendered by default.

424 changes: 424 additions & 0 deletions Rover/ReleaseNotes.txt

Large diffs are not rendered by default.

25 changes: 6 additions & 19 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -9832,28 +9832,15 @@ def RefindGPS(self):

def GPSForYaw(self):
'''Moving baseline GPS yaw'''
self.context_push()
self.load_default_params_file("copter-gps-for-yaw.parm")
self.reboot_sitl()
ex = None
try:
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
m = self.assert_receive_message("GPS2_RAW")
self.progress(self.dump_message_verbose(m))
want = 27000
if abs(m.yaw - want) > 500:
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
self.wait_ready_to_arm()
except Exception as e:
self.print_exception_caught(e)
ex = e

self.context_pop()

self.reboot_sitl()

if ex is not None:
raise ex
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
m = self.assert_receive_message("GPS2_RAW", very_verbose=True)
want = 27000
if abs(m.yaw - want) > 500:
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
self.wait_ready_to_arm()

def SMART_RTL_EnterLeave(self):
'''check SmartRTL behaviour when entering/leaving'''
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -632,15 +632,17 @@ bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg)
msg.external_control = true; // Always true for now. To be filled after PR#28429.
uint8_t fs_iter = 0;
msg.failsafe_size = 0;
if (AP_Notify::flags.failsafe_radio) {
if (rc().in_rc_failsafe()) {
msg.failsafe[fs_iter++] = FS_RADIO;
}
if (battery.has_failsafed()) {
msg.failsafe[fs_iter++] = FS_BATTERY;
}
// TODO: replace flag with function.
if (AP_Notify::flags.failsafe_gcs) {
msg.failsafe[fs_iter++] = FS_GCS;
}
// TODO: replace flag with function.
if (AP_Notify::flags.failsafe_ekf) {
msg.failsafe[fs_iter++] = FS_EKF;
}
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# Barometer setup
BARO DPS310 I2C:0:0x76
BARO BMP280 I2C:0:0x76

# IMU setup

Expand Down

0 comments on commit b11c723

Please sign in to comment.