Skip to content

Commit decd489

Browse files
authored
Merge branch 'master' into master
2 parents 1831add + a69b777 commit decd489

File tree

6 files changed

+19
-20
lines changed

6 files changed

+19
-20
lines changed

ArduPlane/Parameters.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ const AP_Param::Info Plane::var_info[] = {
6060
// @DisplayName: GCS PID tuning mask
6161
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
6262
// @User: Advanced
63-
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing
63+
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
6464
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
6565

6666
// @Param: KFF_RDDRMIX

Tools/AP_Periph/GCS_MAVLink.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ class GCS_MAVLINK_Periph : public GCS_MAVLINK
4141

4242
void send_nav_controller_output() const override {};
4343
void send_pid_tuning() override {};
44+
virtual uint8_t send_available_mode(uint8_t index) const override { return 0; }
4445
};
4546

4647
/*

Tools/autotest/arducopter.py

Lines changed: 6 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9832,28 +9832,15 @@ def RefindGPS(self):
98329832

98339833
def GPSForYaw(self):
98349834
'''Moving baseline GPS yaw'''
9835-
self.context_push()
98369835
self.load_default_params_file("copter-gps-for-yaw.parm")
98379836
self.reboot_sitl()
9838-
ex = None
9839-
try:
9840-
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
9841-
m = self.assert_receive_message("GPS2_RAW")
9842-
self.progress(self.dump_message_verbose(m))
9843-
want = 27000
9844-
if abs(m.yaw - want) > 500:
9845-
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
9846-
self.wait_ready_to_arm()
9847-
except Exception as e:
9848-
self.print_exception_caught(e)
9849-
ex = e
98509837

9851-
self.context_pop()
9852-
9853-
self.reboot_sitl()
9854-
9855-
if ex is not None:
9856-
raise ex
9838+
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
9839+
m = self.assert_receive_message("GPS2_RAW", very_verbose=True)
9840+
want = 27000
9841+
if abs(m.yaw - want) > 500:
9842+
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
9843+
self.wait_ready_to_arm()
98579844

98589845
def SMART_RTL_EnterLeave(self):
98599846
'''check SmartRTL behaviour when entering/leaving'''

Tools/scripts/build_ci.sh

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -243,6 +243,10 @@ for t in $CI_BUILD_TARGET; do
243243
$waf configure --board FreeflyRTK
244244
$waf clean
245245
$waf AP_Periph
246+
echo "Building CubeNode-ETH peripheral fw"
247+
$waf configure --board CubeNode-ETH
248+
$waf clean
249+
$waf AP_Periph
246250
continue
247251
fi
248252

libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
147147

148148
# Barometer setup
149149
BARO DPS310 I2C:0:0x76
150+
BARO BMP280 I2C:0:0x76
150151

151152
# IMU setup
152153

libraries/AP_HAL_QURT/SPIDevice.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,12 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
6767
return transfer_fullduplex(send, (uint8_t*) send, send_len);
6868
}
6969

70+
// Special case handling. This can happen when a send buffer is specified
71+
// even though we are doing only a read.
72+
if (send == recv && send_len == recv_len) {
73+
return transfer_fullduplex(send, recv, send_len);
74+
}
75+
7076
// This is a read transaction
7177
uint8_t buf[send_len+recv_len];
7278
if (send_len > 0) {

0 commit comments

Comments
 (0)