Skip to content

Commit 7f626fa

Browse files
authored
Merge branch 'ArduPilot:master' into loadFactorFix
2 parents 5b68a60 + abc78d1 commit 7f626fa

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

52 files changed

+1112
-112
lines changed

ArduCopter/ReleaseNotes.txt

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,21 @@
11
ArduPilot Copter Release Notes:
22
------------------------------------------------------------------
3+
Copter 4.4.0-beta4 27-July-2023
4+
Changes from 4.4.0-beta3
5+
1) Autopilots specific changes
6+
- Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280)
7+
- DMA for I2C disabled on F7 and H7 boards
8+
- Foxeer H743v1 default serial protocol config fixes
9+
- HeeWing-F405 and F405v2 support
10+
- iFlight BlitzF7 support
11+
2) Scripts may take action based on VTOL motor loss
12+
3) Bug fixes
13+
- BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator)
14+
- CRSFv3 rescans at baudrates to avoid RX loss
15+
- EK3_ABIAS_P_NSE param range fix
16+
- Scripting restart memory corruption bug fixed
17+
- Siyi A8/ZR10 driver fix to avoid crash if serial port not configured
18+
------------------------------------------------------------------
319
Copter 4.4.0-beta3 03-July-2023
420
Changes from 4.4.0-beta2
521
1) Autopilots specific changes
@@ -24,7 +40,6 @@ Changes from 4.4.0-beta2
2440
- SERVOx_PROTOCOL "SToRM32 Gimbal Serial" value renamed to "Gimbal" because also used by Siyi
2541
- SERIALx_OPTION "Swap" renamed to "SwapTXRX" for clarity
2642
- SBF GPS ellipsoid height fixed
27-
- Scripting restart memory corruption bug fixed
2843
- Ublox M10S GPS auto configuration fixed
2944
- ZigZag mode user takeoff fixed (users could not takeoff in ZigZag mode previously)
3045
------------------------------------------------------------------

ArduPlane/config.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,7 @@
238238
#endif
239239

240240
#ifndef OFFBOARD_GUIDED
241-
#define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES
241+
#define OFFBOARD_GUIDED 1
242242
#endif
243243

244244
//////////////////////////////////////////////////////////////////////////////

ArduPlane/qautotune.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88

99
#include "quadplane.h"
1010
#ifndef QAUTOTUNE_ENABLED
11-
#define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED && !HAL_MINIMIZE_FEATURES
11+
#define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED
1212
#endif
1313

1414
#if QAUTOTUNE_ENABLED

ArduPlane/tiltrotor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = {
5454

5555
// @Param: YAW_ANGLE
5656
// @DisplayName: Tilt minimum angle for vectored yaw
57-
// @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output. This needs to be set for Q_TILT_TYPE=3 to enable vectored control for yaw of tricopter tilt quadplanes. This is also used to limit the forwards travel of bicopter tilts when in VTOL modes
57+
// @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output (fully back). This needs to be set in addition to Q_TILT_TYPE=2, to enable vectored control for yaw in tilt quadplanes. This is also used to limit the forward travel of bicopter tilts(Q_TILT_TYPE=3) when in VTOL modes.
5858
// @Range: 0 30
5959
AP_GROUPINFO("YAW_ANGLE", 7, Tiltrotor, tilt_yaw_angle, 0),
6060

Rover/release-notes.txt

Lines changed: 19 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,24 @@
11
Rover Release Notes:
22
------------------------------------------------------------------
3+
Rover 4.4.0-beta4 27-July-2023
4+
Changes from 4.4.0-beta3
5+
1) Autopilots specific changes
6+
- Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280)
7+
- DMA for I2C disabled on F7 and H7 boards
8+
- Foxeer H743v1 default serial protocol config fixes
9+
- HeeWing-F405 and F405v2 support
10+
- iFlight BlitzF7 support
11+
2) Rover specific enhancements
12+
- QuikTune Lua script
13+
- Circle mode safety improvements including handling when CIRC_SPEED set too high
14+
- Velocity controller I-term build-up avoided when steering reaches limits
15+
3) Bug fixes
16+
- BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator)
17+
- CRSFv3 rescans at baudrates to avoid RX loss
18+
- EK3_ABIAS_P_NSE param range fix
19+
- Scripting restart memory corruption bug fixed
20+
- Siyi A8/ZR10 driver fix to avoid crash if serial port not configured
21+
------------------------------------------------------------------
322
Rover 4.4.0-beta3 03-July-2023
423
Changes from 4.4.0-beta2
524
1) Autopilots specific changes
@@ -21,7 +40,6 @@ Changes from 4.4.0-beta2
2140
- SERVOx_PROTOCOL "SToRM32 Gimbal Serial" value renamed to "Gimbal" because also used by Siyi
2241
- SERIALx_OPTION "Swap" renamed to "SwapTXRX" for clarity
2342
- SBF GPS ellipsoid height fixed
24-
- Scripting restart memory corruption bug fixed
2543
- Ublox M10S GPS auto configuration fixed
2644
------------------------------------------------------------------
2745
Rover 4.4.0-beta2 05-Jun-2023

Tools/ardupilotwaf/ap_library.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -271,10 +271,12 @@ def double_precision_check(tasks):
271271

272272
src = str(t.inputs[0]).split('/')[-2:]
273273
if src in double_tasks:
274-
single_precision_option='-fsingle-precision-constant'
275274
t.env.CXXFLAGS = t.env.CXXFLAGS[:]
276-
if single_precision_option in t.env.CXXFLAGS:
277-
t.env.CXXFLAGS.remove(single_precision_option)
275+
for opt in ['-fsingle-precision-constant', '-cl-single-precision-constant']:
276+
try:
277+
t.env.CXXFLAGS.remove(opt)
278+
except ValueError:
279+
pass
278280
t.env.CXXFLAGS.append("-DALLOW_DOUBLE_MATH_FUNCTIONS")
279281

280282

Tools/ardupilotwaf/ardupilotwaf.py

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -303,6 +303,8 @@ def ap_program(bld,
303303
for group in program_groups:
304304
_grouped_programs.setdefault(group, {}).update({tg.name : tg})
305305

306+
return tg
307+
306308

307309
@conf
308310
def ap_example(bld, **kw):
@@ -354,7 +356,7 @@ def ap_stlib_target(self):
354356
self.target = '#%s' % os.path.join('lib', self.target)
355357

356358
@conf
357-
def ap_find_tests(bld, use=[]):
359+
def ap_find_tests(bld, use=[], DOUBLE_PRECISION_SOURCES=[]):
358360
if not bld.env.HAS_GTEST:
359361
return
360362

@@ -368,7 +370,7 @@ def ap_find_tests(bld, use=[]):
368370
includes = [bld.srcnode.abspath() + '/tests/']
369371

370372
for f in bld.path.ant_glob(incl='*.cpp'):
371-
ap_program(
373+
t = ap_program(
372374
bld,
373375
features=features,
374376
includes=includes,
@@ -379,6 +381,16 @@ def ap_find_tests(bld, use=[]):
379381
use_legacy_defines=False,
380382
cxxflags=['-Wno-undef'],
381383
)
384+
filename = os.path.basename(f.abspath())
385+
if filename in DOUBLE_PRECISION_SOURCES:
386+
t.env.CXXFLAGS = t.env.CXXFLAGS[:]
387+
single_precision_option='-fsingle-precision-constant'
388+
if single_precision_option in t.env.CXXFLAGS:
389+
t.env.CXXFLAGS.remove(single_precision_option)
390+
single_precision_option='-cl-single-precision-constant'
391+
if single_precision_option in t.env.CXXFLAGS:
392+
t.env.CXXFLAGS.remove(single_precision_option)
393+
t.env.CXXFLAGS.append("-DALLOW_DOUBLE_MATH_FUNCTIONS")
382394

383395
_versions = []
384396

Tools/ardupilotwaf/boards.py

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -243,23 +243,28 @@ def configure_env(self, cfg, env):
243243
if 'clang' in cfg.env.COMPILER_CC:
244244
env.CFLAGS += [
245245
'-fcolor-diagnostics',
246-
247246
'-Wno-gnu-designator',
248247
'-Wno-inconsistent-missing-override',
249248
'-Wno-mismatched-tags',
250249
'-Wno-gnu-variable-sized-type-not-at-end',
251250
'-Werror=implicit-fallthrough',
251+
'-cl-single-precision-constant',
252+
]
253+
env.CXXFLAGS += [
254+
'-cl-single-precision-constant',
252255
]
253256
else:
254257
env.CFLAGS += [
255258
'-Wno-format-contains-nul',
259+
'-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f
256260
]
257261
if self.cc_version_gte(cfg, 7, 4):
258262
env.CXXFLAGS += [
259263
'-Werror=implicit-fallthrough',
260264
]
261265
env.CXXFLAGS += [
262266
'-fcheck-new',
267+
'-fsingle-precision-constant',
263268
]
264269

265270
if cfg.env.DEBUG:
@@ -878,7 +883,6 @@ def expand_path(p):
878883
env.CFLAGS += [
879884
'-fno-inline-functions',
880885
'-mlongcalls',
881-
'-fsingle-precision-constant',
882886
]
883887
env.CFLAGS.remove('-Werror=undef')
884888

@@ -894,7 +898,6 @@ def expand_path(p):
894898
'-Wno-sign-compare',
895899
'-fno-inline-functions',
896900
'-mlongcalls',
897-
'-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f
898901
'-fno-threadsafe-statics',
899902
'-DCYGWIN_BUILD']
900903
env.CXXFLAGS.remove('-Werror=undef')
@@ -957,7 +960,6 @@ def configure_env(self, cfg, env):
957960
env.CFLAGS += cfg.env.CPU_FLAGS + [
958961
'-Wlogical-op',
959962
'-Wframe-larger-than=1300',
960-
'-fsingle-precision-constant',
961963
'-Wno-attributes',
962964
'-fno-exceptions',
963965
'-Wall',

Tools/autotest/arducopter.py

Lines changed: 57 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -3833,7 +3833,7 @@ def PrecisionLanding(self):
38333833
new_pos = self.mav.location()
38343834
delta = self.get_distance(target, new_pos)
38353835
self.progress("Landed %f metres from target position" % delta)
3836-
max_delta = 1
3836+
max_delta = 1.5
38373837
if delta > max_delta:
38383838
raise NotAchievedException("Did not land close enough to target position (%fm > %fm" % (delta, max_delta))
38393839

@@ -4550,7 +4550,7 @@ def precision_loiter_to_pos(self, x, y, z, timeout=40):
45504550
# determine if we've successfully navigated to close to
45514551
# where we should be:
45524552
dist = math.sqrt(delta_ef.x * delta_ef.x + delta_ef.y * delta_ef.y)
4553-
dist_max = 0.15
4553+
dist_max = 1
45544554
self.progress("dist=%f want <%f" % (dist, dist_max))
45554555
if dist < dist_max:
45564556
# success! We've gotten within our target distance
@@ -6896,7 +6896,7 @@ def shove(a, b):
68966896
if self.get_sim_time_cached() - tstart > 10:
68976897
break
68986898
vel = self.get_body_frame_velocity()
6899-
if vel.length() > 0.3:
6899+
if vel.length() > 0.5:
69006900
raise NotAchievedException("Moved too much (%s)" %
69016901
(str(vel),))
69026902
shove(None, None)
@@ -7687,29 +7687,19 @@ def fly_rangefinder_mavlink_distance_sensor(self):
76877687

76887688
def GSF(self):
76897689
'''test the Gaussian Sum filter'''
7690-
ex = None
76917690
self.context_push()
7692-
try:
7693-
self.set_parameter("EK2_ENABLE", 1)
7694-
self.reboot_sitl()
7695-
self.takeoff(20, mode='LOITER')
7696-
self.set_rc(2, 1400)
7697-
self.delay_sim_time(5)
7698-
self.set_rc(2, 1500)
7699-
self.progress("Path: %s" % self.current_onboard_log_filepath())
7700-
dfreader = self.dfreader_for_current_onboard_log()
7701-
self.do_RTL()
7702-
except Exception as e:
7703-
self.progress("Caught exception: %s" %
7704-
self.get_exception_stacktrace(e))
7705-
ex = e
7706-
7691+
self.set_parameter("EK2_ENABLE", 1)
7692+
self.reboot_sitl()
7693+
self.takeoff(20, mode='LOITER')
7694+
self.set_rc(2, 1400)
7695+
self.delay_sim_time(5)
7696+
self.set_rc(2, 1500)
7697+
self.progress("Path: %s" % self.current_onboard_log_filepath())
7698+
dfreader = self.dfreader_for_current_onboard_log()
7699+
self.do_RTL()
77077700
self.context_pop()
77087701
self.reboot_sitl()
77097702

7710-
if ex is not None:
7711-
raise ex
7712-
77137703
# ensure log messages present
77147704
want = set(["XKY0", "XKY1", "NKY0", "NKY1"])
77157705
still_want = want
@@ -7719,6 +7709,46 @@ def GSF(self):
77197709
raise NotAchievedException("Did not get %s" % want)
77207710
still_want.remove(m.get_type())
77217711

7712+
def GSF_reset(self):
7713+
'''test the Gaussian Sum filter based Emergency reset'''
7714+
self.context_push()
7715+
self.set_parameters({
7716+
"COMPASS_ORIENT": 4, # yaw 180
7717+
"COMPASS_USE2": 0, # disable backup compasses to avoid pre-arm failures
7718+
"COMPASS_USE3": 0,
7719+
})
7720+
self.reboot_sitl()
7721+
self.change_mode('GUIDED')
7722+
self.wait_ready_to_arm()
7723+
7724+
# record starting position
7725+
startpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
7726+
self.progress("startpos=%s" % str(startpos))
7727+
7728+
# arm vehicle and takeoff to at least 5m
7729+
self.arm_vehicle()
7730+
expected_alt = 5
7731+
self.user_takeoff(alt_min=expected_alt)
7732+
7733+
# watch for emergency yaw reset
7734+
self.wait_text("EKF3 IMU. emergency yaw reset", timeout=5, regex=True)
7735+
7736+
# record how far vehicle flew off
7737+
endpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
7738+
delta_x = endpos.x - startpos.x
7739+
delta_y = endpos.y - startpos.y
7740+
dist_m = math.sqrt(delta_x*delta_x + delta_y*delta_y)
7741+
self.progress("GSF yaw reset triggered at %f meters" % dist_m)
7742+
7743+
self.do_RTL()
7744+
self.context_pop()
7745+
self.reboot_sitl()
7746+
7747+
# ensure vehicle did not fly too far
7748+
dist_m_max = 8
7749+
if dist_m > dist_m_max:
7750+
raise NotAchievedException("GSF reset failed, vehicle flew too far (%f > %f)" % (dist_m, dist_m_max))
7751+
77227752
def fly_rangefinder_mavlink(self):
77237753
self.fly_rangefinder_mavlink_distance_sensor()
77247754

@@ -9267,8 +9297,8 @@ def FETtecESC_safety_switch(self):
92679297
# before the motors will spin:
92689298
self.wait_esc_telem_rpm(
92699299
esc=mot,
9270-
rpm_min=17640,
9271-
rpm_max=17640,
9300+
rpm_min=17626,
9301+
rpm_max=17626,
92729302
minimum_duration=2,
92739303
timeout=5,
92749304
)
@@ -9277,8 +9307,8 @@ def FETtecESC_safety_switch(self):
92779307
self.set_safetyswitch_off()
92789308
self.wait_esc_telem_rpm(
92799309
esc=mot,
9280-
rpm_min=17640,
9281-
rpm_max=17640,
9310+
rpm_min=17626,
9311+
rpm_max=17626,
92829312
minimum_duration=2,
92839313
timeout=5,
92849314
)
@@ -9861,6 +9891,7 @@ def tests2b(self): # this block currently around 9.5mins here
98619891
self.AltEstimation,
98629892
self.EKFSource,
98639893
self.GSF,
9894+
self.GSF_reset,
98649895
self.AP_Avoidance,
98659896
self.SMART_RTL,
98669897
self.RTL_TO_RALLY,

Tools/autotest/common.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6766,7 +6766,7 @@ def get_speed_vector(self, timeout=1):
67666766
return Vector3(msg.vx, msg.vy, msg.vz)
67676767

67686768
"""Wait for a given speed vector."""
6769-
def wait_speed_vector(self, speed_vector, accuracy=0.2, timeout=30, **kwargs):
6769+
def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs):
67706770
def validator(value2, target2):
67716771
return (math.fabs(value2.x - target2.x) <= accuracy and
67726772
math.fabs(value2.y - target2.y) <= accuracy and
@@ -8450,11 +8450,11 @@ def SetHome(self):
84508450
start_loc = self.sitl_start_location()
84518451
self.progress("SITL start loc: %s" % str(start_loc))
84528452
delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)
8453-
if delta > 0.000001:
8453+
if delta > 0.000006:
84548454
raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %
84558455
(orig_home.latitude * 1.0e-7, start_loc.lat, delta))
84568456
delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)
8457-
if delta > 0.000001:
8457+
if delta > 0.000006:
84588458
raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %
84598459
(orig_home.longitude * 1.0e-7, start_loc.lng, delta))
84608460
if self.is_rover():

Tools/autotest/helicopter.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -403,7 +403,7 @@ def ManAutoRotation(self, timeout=600):
403403
self.progress("Triggering manual autorotation by disabling interlock")
404404
self.set_rc(3, 1300)
405405
self.set_rc(8, 1000)
406-
self.wait_servo_channel_value(8, 1200, timeout=3)
406+
self.wait_servo_channel_value(8, 1199, timeout=3)
407407
self.progress("channel 8 set to autorotation window")
408408

409409
self.set_rc(8, 2000)

Tools/scripts/size_compare_branches.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,7 @@ def __init__(self,
156156
'Pixhawk1-1M-bdshot',
157157
'Pixhawk1-bdshot',
158158
'SITL_arm_linux_gnueabihf',
159+
'RADIX2HD',
159160
])
160161

161162
# blacklist all linux boards for bootloader build:

0 commit comments

Comments
 (0)