Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
YI-BOYANG authored Nov 15, 2024
2 parents 1831add + a69b777 commit decd489
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 20 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),

// @Param: KFF_RDDRMIX
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Periph/GCS_MAVLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ class GCS_MAVLINK_Periph : public GCS_MAVLINK

void send_nav_controller_output() const override {};
void send_pid_tuning() override {};
virtual uint8_t send_available_mode(uint8_t index) const override { return 0; }
};

/*
Expand Down
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: 4 additions & 0 deletions Tools/scripts/build_ci.sh
Original file line number Diff line number Diff line change
Expand Up @@ -243,6 +243,10 @@ for t in $CI_BUILD_TARGET; do
$waf configure --board FreeflyRTK
$waf clean
$waf AP_Periph
echo "Building CubeNode-ETH peripheral fw"
$waf configure --board CubeNode-ETH
$waf clean
$waf AP_Periph
continue
fi

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
6 changes: 6 additions & 0 deletions libraries/AP_HAL_QURT/SPIDevice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,12 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
return transfer_fullduplex(send, (uint8_t*) send, send_len);
}

// Special case handling. This can happen when a send buffer is specified
// even though we are doing only a read.
if (send == recv && send_len == recv_len) {
return transfer_fullduplex(send, recv, send_len);
}

// This is a read transaction
uint8_t buf[send_len+recv_len];
if (send_len > 0) {
Expand Down

0 comments on commit decd489

Please sign in to comment.