Rover-4.4.0-beta1 available for beta testing

Rover-4.4.0-beta1 has been released for beta testing and can be installed using MP or QGC’s beta firmwares link. Alternatively it can be manually downloaded from firmware.ardupilot.org.

The changes vs 4.3.0-beta12 are in the release notes and also copied below.

  1. New autopilots supported
    • ESP32
    • Flywoo Goku F405S AIO
    • Foxeer H743v1
    • MambaF405-2022B
    • PixPilot-V3
    • PixSurveyA2
    • rFCU H743
    • ThePeach K1/R1
  2. Autopilot specific changes
    • Bi-Directional DShot support for CubeOrangePlus-bdshot, CUAVNora+, MatekF405TE/VTOL-bdshot, MatekL431, Pixhawk6C-bdshot, QioTekZealotH743-bdshot
    • Bi-Directional DShot up to 8 channels on MatekH743
    • BlueRobotics Navigator supports baro on I2C bus 6
    • BMP280 baro only for BeastF7, KakuteF4, KakuteF7Mini, MambaF405, MatekF405, Omnibusf4 to reduce code size (aka “flash”)
    • CSRF and Hott telemetry disabled by default on some low power boards (aka “minimised boards”)
    • Foxeer Reaper F745 supports external compasses
    • OmnibusF4 support for BMI270 IMU
    • OmnibusF7V2-bdshot support removed
    • KakuteF7 regains displayport, frees up DMA from unused serial port
    • KakuteH7v2 gets second battery sensor
    • MambaH743v4 supports VTX
    • MatekF405-Wing supports InvensenseV3 IMUs
    • PixPilot-V6 heater enabled
    • Raspberry 64OS startup crash fixed
    • ReaperF745AIO serial protocol defaults fixed
    • SkystarsH7HD (non-bdshot) removed as users should always use -bdshot version
    • Skyviper loses many unnecessary features to save flash
    • UBlox GPS only for AtomRCF405NAVI, BeastF7, MatekF405, Omnibusf4 to reduce code size (aka “flash”)
    • VRBrain-v52 and VRCore-v10 features reduced to save flash
  3. Driver enhancements
    • ARK RTK GPS support
    • BMI088 IMU filtering and timing improved, ignores bad data
    • CRSF OSD may display disarmed state after flight mode (enabled using RC_OPTIONS)
    • Daiwa winch baud rate obeys SERIALx_BAUD parameter
    • EFI supports fuel pressure and ignition voltage reporting and battery failsafe
    • ICM45686 IMU support
    • ICM20602 uses fast reset instead of full reset on bad temperature sample (avoids occasional very high offset)
    • ICM45686 supports fast sampling
    • MAX31865 temp sensor support
    • MB85RS256TY-32k, PB85RS128C and PB85RS2MC FRAM support
    • MMC3416 compass orientation fix
    • MPPT battery monitor reliability improvements, enable/disable aux function and less spammy
    • Multiple USD-D1-CAN radar support
    • NMEA output rate configurable (see NMEA_RATE_MS)
    • NMEA output supports PASHR message (see NMEA_MSG_EN)
    • OSD supports average resting cell voltage (see OSD_ACRVOLT_xxx params)
    • Rockblock satellite modem support
    • Serial baud support for 2Mbps (only some hardware supports this speed)
    • SF45b lidar filtering reduced (allows detecting smaller obstacles
    • SmartAudio 2.0 learns all VTX power levels)
    • UAVCAN ESCs report error count using ESC Telemetry
    • Unicore GPS (e.g. UM982) support
    • VectorNav 100 external AHRS support
    • 5 IMUs supported
  4. EKF related enhancements
    • Baro compensation using wind estimates works when climbing or descending (see BAROx_WCF_UP/DN)
    • External AHRS support for enabling only some sensors (e.g. IMU, Baro, Compass) see EAHRS_SENSORS
    • Magnetic field tables updated
    • Non-compass initial yaw alignment uses GPS course over GSF (mostly affects Planes and Rover)
  5. Control and navigation enhancements
    • DO_SET_ROI_NONE command turns off ROI
    • JUMP_TAG mission item support
    • Manual mode steering expo configurable (see MANUAL_STR_EXPO)
    • Missions can be stored on SD card (see BRD_SD_MISSION)
    • NAV_SCRIPT_TIME command accepts floating point arguments
    • Pause/Resume returns success if mission is already paused or resumed
  6. Camera and gimbal enhancements
    • BMMCC support included in Servo driver
    • DJI RS2/RS3-Pro gimbal support
    • Dual camera support (see CAM2_TYPE)
    • Gimbal/Mount2 can be moved to retracted or neutral position
    • Gremsy ZIO support
    • IMAGE_START_CAPTURE, SET_CAMERA_ZOOM/FOCUS, VIDEO_START/STOP_CAPTURE command support
    • Paramters renamed and rescaled
      • CAM_TRIGG_TYPE renamed to CAM1_TYPE and options have changed
      • CAM_DURATION renamed to CAM1_DURATION and scaled in seconds
      • CAM_FEEDBACK_PIN/POL renamed to CAM1_FEEBAK_PIN/POL
      • CAM_MIN_INTERVAL renamed to CAM1_INTRVAL_MIN and scaled in seconds
      • CAM_TRIGG_DIST renamed to CAMx_TRIGG_DIST and accepts fractional values
    • RunCam2 4k support
    • ViewPro camera gimbal support
  7. Logging changes
    • BARD msg includes 3-axis dynamic pressure useful for baro compensation of wind estimate
    • MCU log msg includes main CPU temp and voltage (was part of POWR message)
    • RCOut banner message always included in Logs
    • SCR message includes memory usage of all running scripts
    • CANS message includes CAN bus tx/rx statistics
    • Home location not logged to CMD message
    • MOTB message includes throttle output
  8. Scripting enhancements
    • EFI Skypower driver gets improved telem messages and bug fixes
    • Generator throttle control example added
    • Heap max increased by allowing heap to be split across multiple underlying OS heaps
    • Hexsoon LEDs applet
    • Logging from scripts supports more formats
    • Parameters can be removed or reordered
    • Parameter description support (scripts must be in AP’s applet or driver directory)
    • Rangefinder driver support
    • Runcam_on_arm applet starts recording when vehicle is armed
    • Safety switch, E-Stop and motor interlock support
    • Scripts can restart all scripts
    • Script_Controller applet supports inflight switching of active scripts
  9. Custom build server enhancements
    • AIS support for displaying nearby boats can be included
    • Battery, Camera and Compass drivers can be included/excluded
    • EKF3 wind estimation can be included/excluded
    • PCA9685, ToshibaLED, PLAY_TUNE notify drivers can be included/excluded
    • RichenPower generator can be included/excluded
    • RC SRXL protocol can be excluded
    • SIRF GPSs can be included/excluded
  10. Safety related enhancements and fixes
    • Arming check for servo outputs skipped when SERVOx_FUNCTION is scripting
    • Arming check fix if both “All” and other bitmasks are selected (previously only ran the other checks)
    • GCS failsafe timeout is configurable (see FS_GCS_TIMEOUT)
    • “EK3 sources require RangeFinder” pre-arm check fix when user only sets up 2nd rangefinder (e.g. 1st is disabled)
    • Pre-arm check that low and critical battery failsafe thresholds are different
    • Pre-arm message fixed if 2nd EKF core unhealthy
    • Pre-arm check if reboot required to enabled IMU batch sampling (used for vibe analysis)
    • RC failsafe timeout configurable (see RC_FS_TIMEOUT)
  11. Minor enhancements
    • Boot time reduced by improving parameter conversion efficiency
    • BRD_SAFETYENABLE parameter renamed to BRD_SAFETY_DEFLT
    • Compass calibration auxiliary switch function (set RCx_OPTION=171)
    • Disable IMU3 auxiliary switch function (set RCx_OPTION=110)
    • Rangefinder and FS_OPTIONS param conversion code reduced (affects when upgrading from 3.6 or earlier)
    • MAVFTP supports file renaming
    • MAVLink in-progress reply to some requests for calibration from GCS
  12. Bug fixes:
    • ADSB telemetry and callsign fixes
    • Battery pct reported to GCS limited to 0% to 100% range
    • Bi-directional DShot fix on H7 boards after system time wrap (more complete fix than in 4.3.6)
    • DisplayPort OSD screen reliability improvement on heavily loaded OSDs especially F4 boards
    • DisplayPort OSD artificial horizon better matches actual horizon
    • EFI Serial MS bug fix to avoid possible infinite loop
    • EKF3 Replay fix when COMPASS_LEARN=3
    • ESC Telemetry external temp reporting fix
    • Fence upload works even if Auto mode is excluded from firmware
    • FMT messages logged even when Fence is exncluded from firmware (e.g. unselected when using custom build server)
    • Hardfault avoided if user changes INS_LOG_BAT_CNT while batch sampling running
    • ICM20649 temp sensor tolerate increased to avoid unnecessary FIFO reset
    • IMU detection bug fix to avoid duplicates
    • IMU temp cal fix when using auxiliary IMU
    • Message Interval fix for restoring default rate GCS_MAVLink: fix set-default-rate of a message we don't send by default by peterbarker · Pull Request #21947 · ArduPilot/ardupilot · GitHub
    • RADIO_STATUS messages slow-down feature never completely stops messages from being sent
    • SERVOx_TRIM value output momentarily if SERVOx_FUNCTION is changed from Disabled to RCPassThru, RCIN1, etc. Avoids momentary divide-by-zero
    • Scripting file system open fix
    • Scripting PWM source deletion crash fix
    • MAVFTP fix for low baudrates (4800 baud and lower)
    • ModalAI VOXL reset handling fix
    • MPU6500 IMU fast sampling rate to 4k (was 1K)
    • NMEA GPGGA output fixed for GPS quality, num sats and hdop
    • Position control reset avoided even with very uneven main loop rate due to high CPU load
    • Throttle notch FFT tuning param fix
    • VTX protects against pitmode changes when not enabled or vehicle disarmed
  13. Developer specific items
    • DroneCAN replaces UAVCAN
    • FlighAxis simulator rangefinder fixed
    • Scripts in applet and drivers directory checked using linter
    • Simulator supports main loop timing jitter (see SIM_TIME_JITTER)
    • Simulink model and init scripts
    • SITL on hardware support (useful to demo servos moving in response to simulated flight)
    • SITL parameter definitions added (some, not all)
    • Webots 2023a simulator support
    • XPlane support for wider range of aircraft

Any testing and feedback is greatly appreciated!

4 Likes

Some outstanding leaps forward for sure. What’s the plan for improving the navigation controller?

2 Likes

Yes, this definitely needs a bit of ‘tuning’

@Yuri_Rage, @John_Easton,

Yes, this is the key thing that we need to sort out. We certainly can’t go through another major release cycle without Rover/Boat getting released too.

So I think the issues we need to solve are:

  1. Straight line navigation performance (reported by JohnE and Xianglunkai, issue)
  2. WP radius issue (reported by Yuri, issue)

These are some ideas that I have for solutions:

  • Rover AutoTune of speed, turn rate controller, velocity controller based on logic used by VTOL quick tune script (multicopter video)
  • Add WP_ACCEL_C parameter that Copter’s SCurve already has and allows more control over how much the corners are cut. This is quite easy.
  • Add the ability to overshoot corners. This is medium difficulty.
  • Allow SCurve navigation to handle overspeeding vehicles (e.g. moving too quickly and unable to slow down). Currently we support underspeed vehicles (e.g. driving too slow and can’t reach target speed) but not those driving too quickly. This is probably easy-ish.
  • Add back L1 navigation as an option. This would likely be a re-implementation of L1 because the original L1 was only a lateral controller. This is quite difficult but worst case I can do this of course.

I’ve just started on a Rover AutoTune mode a few days ago. My idea is that the vehicle will drive in a large circle (radius configurable with an ATUN_RADIUS parameter). Then we attempt to tune speed, then turn rate, then finally the velocity control (which is the most critical part of navigation and what is probably causing the wobbles).

Although I want to base the tuning logic on the VTOL quicktune there may be some problems. The VTOL quicktune method basically raises the gains until it notices oscillation and then it backs off the gains. This works for PID controllers but our speed and turn-rate controllers also use Feed Forward (in fact it is the most critical gain) so we probably need a different approach for these. I’m thinking maybe we use a sin curve to generate a desired speed (or turn rate) and then adjust the FF gain until the amplitude of the desired and actual matches.

I should preface this with some more analysis of all the bad log files that you two and others have provided me.

What do you think?

3 Likes

Firstly, I really appreciate the ton of work you and the ArduPilot team put into this over and above day to day work and family.
I have just got back from a four day survey so I have a ton of logs, some very large (>6 hour missions).
Just looking at the sonar data acquired, it looks pretty good but here are some of the issues I ran into:
1 - Straight line wpt to wpt still has some oscillating even in very calm conditions
2 - Over throttling in the corners, especially tight corners, this aggressive throttling causes major interference with the sonar
3 - If wpts are closer than twenty meters apart the craft appears to get ‘lost’ momentarily and makes loop like attempts to get back on track.

1 Like

@John_Easton,

Thanks for that… a few thoughts from me on this…

I forgot to mention one thing which is that AP actually has “oscillation protection” built in and it can be activated by setting the _SMAX parameter on the appropriate PID. So for example to enable the oscillation protection on the turn rate controller we could set ATC_STR_RAT_SMAX to something like 10 or 50.

I’m not immediately suggesting this is the solution to the wobbles in straight lines issue though. It’s just something that I came across as part of a review of the VTOL Quicktune lua script mentioned above.

Item 3 is very likely the overspeed issue I think. The vehicle cannot decelerate as quickly as the SCurve generated path requires which leads to the vehicle getting ahead of the target point and then it does a loop around to get back on track. I’ve reproduced this issue in SITL.

2 Likes

“ATC_STR_RAT_SMAX to something like 10 or 50.” - very interesting

I will try get a video so you can hear the throttle when she makes a turn, especially if it is more than 40° or so.

I must admit I feel a little guilty for immediately calling attention to the elephant in the room, so thank you much for the quick and very encouraging reply, Randy.

I really like the idea of autotune for Rover, and your approach seems very reasonable. If the path is auto-generated and intentionally deviates from that which we can plan and see in Mission Planner, it’d be good to have some constraint or control over it wandering too far.

I think the two issues are slightly related - overshooting every pivoted waypoint sets the controller up for failure from the start, essentially providing the setup for any proclivity to oscillate on the next straight leg.

While overspeeding is likely part of the WP_RADIUS issue (and possibly simply an issue of its own), I think there may be an underlying logic error, as well, as identified in the GitHub issue I raised.

More refined control of cornering sounds excellent! WP_ACCEL_C would certainly be a welcome addition, and I know we’re aware of at least one use case for corner overshoots, as well.

I appreciate that reviving L1 nav is an option, and I know there’s some community inertia to simply keep it, but there’s a lot of promise in the Copter-like nav controller, so long as the issues are addressed. It already produces outstanding results on all-electric vehicles with very linear, predictable (and very responsive) throttle/steering behavior - we just need some tweaking such that those results are achievable in tougher to tune vehicles like boats or servo-adapted hydrostatic drives (mowers/ag applications).

And very interesting about the _SMAX param! I haven’t yet touched that one but may experiment a bit.

4 Likes

A “circle” waypoint, similar to the loiter waypoint in plane/copter, would be really cool for rover, but only if it worked for small circles (radius 2 or 3, or even 1.5 or 2.5, meters), driven at about 1-1.5 m/sec. I suspect many mower applications would find it useful to mow circles around trees.

1 Like

@Christopher_Milner,

Great, thanks for the confirmation on adding support for Circle mode. I think we will add this… it just makes sense to have the standalone mode if we also need it for autotune.

1 Like

@rmackay9 - would be great to incorporate that circle mode into some sort of waypoint control (or script time) such that it could be used for geo-based avoidance in the way that Chris suggests. Would render all of my complaints about BendyRuler completely moot.

2 Likes

Trying this 4.4 Ardurover beta version (Sat Apr 22 11:23:37 2023) on a Beaglebone Black with a BBBmini connected

$ sudo /opt/scripts/tools/version.sh
git:/opt/scripts/:[1b1122751f7051bd8996f353756ba6ff30e71820]
eeprom:[A335BNLT00C01319BBBK0A8C]
model:[TI_AM335x_BeagleBone_Black]
dogtag:[BeagleBoard.org Debian Buster Console Image 2023-04-06]
bootloader:[eMMC-(default)]:[/dev/mmcblk1]:[U-Boot SPL 2019.04-g923f8b8 (Jan 02 2022 - 19:05:15 +0000)]:[location: dd MBR]
bootloader:[eMMC-(default)]:[/dev/mmcblk1]:[U-Boot 2019.04-g923f8b8]:[location: dd MBR]
UBOOT: Booted Device-Tree:[am335x-boneblack-uboot-univ.dts]
UBOOT: Loaded Overlay:[AM335X-PRU-UIO-00A0]
UBOOT: Loaded Overlay:[BB-ADC-00A0.kernel]
UBOOT: Loaded Overlay:[BB-BONE-eMMC1-01-00A0.kernel]
UBOOT: Loaded Overlay:[BB-SPIDEV1-00A0.kernel]
kernel:[4.19.232-bone-rt-r75]
device-tree-override:[dtb=am335x-boneblack-bbbmini.dtb]
/boot/uEnv.txt Settings:
uboot_overlay_options:[enable_uboot_overlays=1]
uboot_overlay_options:[disable_uboot_overlay_video=1]
uboot_overlay_options:[uboot_overlay_pru=AM335X-PRU-UIO-00A0.dtbo]
uboot_overlay_options:[enable_uboot_cape_universal=1]
pkg check: to individually upgrade run: [sudo apt install --only-upgrade <pkg>]
pkg:[bb-cape-overlays]:[4.14.20210821.0-0~buster+20210821]
pkg:[bb-customizations]:[1.20221108.0-0~buster+20221108]
pkg:[bb-usb-gadgets]:[1.20230414.0-0~buster+20230414]
pkg:[bb-wl18xx-firmware]:[1.20230414.0-0~buster+20230414]
pkg:[kmod]:[26-1]
WARNING:pkg:[librobotcontrol]:[NOT_INSTALLED]
pkg:[firmware-ti-connectivity]:[20190717-2rcnee1~buster+20200305]
groups:[debian : debian adm kmem dialout cdrom floppy audio dip video plugdev users systemd-journal input bluetooth netdev gpio admin i2c tisdk weston-launch cloud9ide]
cmdline:[console=ttyS0,115200n8 bone_capemgr.uboot_capemgr_enabled=1 root=/dev/mmcblk1p1 ro rootfstype=ext4 rootwait coherent_pool=1M net.ifnames=0 lpj=1990656 rng_core.default_quality=100 quiet]
dmesg | grep remote
[    1.715159] remoteproc remoteproc0: wkup_m3 is available
[    1.893713] remoteproc remoteproc0: powering up wkup_m3
[    1.893743] remoteproc remoteproc0: Booting fw image am335x-pm-firmware.elf, size 217148
[    1.894011] remoteproc remoteproc0: remote processor wkup_m3 is now up
dmesg | grep pru
dmesg | grep pinctrl-single
[    1.209829] pinctrl-single 44e10800.pinmux: 142 pins, size 568
dmesg | grep gpio-of-helper
[    1.229568] gpio-of-helper ocp:cape-universal: ready
END

towards mounting a balance bot with two DC motors controlled by PWM signals (MOT_PWM_TYPE=3) generated on BBBmini pins RC_11/P8_46 and RC_12/P8_45.

Controlling this with MP, it connects, RC receiver pulses arrive correctly and the hud moves correctly when moving the board, but trying MP Motor Test with two oscilloscope probes on RC_11/P8_46 and RC_12/P8_45, no matter what I try, there are no PWM signals at all.

If instead I try to generate RC pulses (MOT_PWM_TYPE=0) with MP Motor Test, they appear correctly:

PWM signals can be generated manually with a script such as this:

#!/bin/bash
sudo config-pin P8_45 pwm
sudo config-pin P8_46 pwm
PWM=/sys/class/pwm/pwmchip7/pwm0
echo 100000 > ${PWM}/period
echo 33333 > ${PWM}/duty_cycle
echo 1 > ${PWM}/enable
PWM=/sys/class/pwm/pwmchip7/pwm1
echo 100000 > ${PWM}/period
echo 66666 > ${PWM}/duty_cycle
echo 1 > ${PWM}/enable

So before trying hateful workarounds such as:
-a pair of old brushed controllers used in R/C (common before brushless ones),
-a dual DC motor controller accepting R/C pulses as inputs,
-an Arduino converting two R/C pulses 1000/1500/2000µs to two 0/50/100% PWM signals,
what can I try?

For some strange reason, on this script period has a narrow range (100000-100009):

$ echo 99999 > /sys/class/pwm/pwmchip7/pwm0/period
-bash: echo: write error: Invalid argument
$ echo 100000 > /sys/class/pwm/pwmchip7/pwm0/period
$ echo 100009 > /sys/class/pwm/pwmchip7/pwm0/period
$ echo 100010 > /sys/class/pwm/pwmchip7/pwm0/period
-bash: echo: write error: Invalid argument

so I changed MOT_PWM_FREQ=10 (it was 1KHz before).

This caused a marginal appearance of 10KHz PWM signals:


but they appear briefly, with low duty cycle (testing at MP Motors Test 50% duty cycle), and even after stopping motors.

So I inserted an Arduino for generating the PWM signals required by the dual motor controller installed in the balance bot with Beaglebone Black + BBBmini from the R/C PDM signals obtained with MOT_PWM_TYPE=0, and it worked:

But then, reviewing logs I found that the wheel encoders signals didn’t appear, although they were correctly generated. For the left wheel, the direct and quadrature signals were:


(BTW, the encoder admits being supplied at 3.3V)
The relevant parameters:

WENC_PINA,89
WENC_PINB,87
WENC_TYPE,1
WENC2_PINA,76
WENC2_PINB,77
WENC2_TYPE,1

and the connections on BBBmini:

WENC_PINA	RC_3	P8_30	89
WENC_PINB	RC_4 	P8_29	87
WENC2_PINA	RC_5	P8_40	77
WENC2_PINB	RC_6	P8_39	76

Nothing appeared reviewing logs with MP:
Barbie20_NoWENCs

I tried the latest development version and the same happened, so I fear that encoder signals with their complexity (edge interrupts needed) are not supported, but this, as well all about PWM not working, is not mentioned in List of Firmware Limitations by Board — Rover documentation

Am I missing something about PWM and encoders for Ardurover on Beaglebone Black with BBBmini?

Thank you, rmackay9 and others for your efforts.

Beyond reporting that I, too, find the new navigation unsatisfactory compared to 4.2.3, what else would you like to know?

Are there settings I should try to adjust? (I’ll re-read Yuri’s ticket)

I’ve had good, repeatable navigation with
WP_RADIUS,0.100584

Last year I worked through a variation of a spiral pattern and can overlap less than a foot each time and have a Plan I can execute repeatedly - it even passed the “what about 6 months later?” test this spring, running the same route.
I’m running RTK and GPS-YAW using F9P modules, with a third F9P as my local base and RTCM correction source.

Today, I upgraded to 4.4.0-beta 1 and tried to run the same Mission.

It didn’t even successfully navigate to/through WP 1, and it approached WP1 quite slowly.

I restored 4.2.3 and it cruised over to WP1, made the turn, and proceeded to complete the mission.

I re-flashed 4.4.0-beta1 and tried again - same results as the first, slowly creep up on WP1 and never reach it, never proceed.

I even relaxed the WP radius

WP_RADIUS,0.201168

With no improvement.

Unrelated, I also tried to move my Ublox MB GPS (18) from serial to a L431 CAN device, changing the type to 23 and the CAN address, then on the L431 I set the GPS as type 18.

I did get a 3D GPS fix out of it, but never Float or Fixed - I suspect it wasn’t receiving corrections from the first GPS, which are supposed to go through the flight controller in the auto configuration.

I wound up going back to serial GPS.

I did successfully get a Cygbot D1 Lidar to work on Serial 5. I had no luck with running it through the CAN L431, but I have another Matek L431 coming to try. Connecting serially, it worked fine.

The problems I have with that are not currently related to the Beta of Rover - I need to figure out how to position the 3D Lidar to not see every bump in the ground as an obstacle. I’ve elevated it some, I need to elevate the angle some more.

1 Like

Hi @tsm1mt,

Thanks very much for testing and sorry for the delay in responding.

I’m working on an AutoTune mode for Rover and a minor navigation fix that I hope will resolve the problems people are seeing.

I suspect though that the navigation issues you’re seeing are not directly related to this. Could you post an onboard log?

1 Like

The logs from that earlier run were empty (and so, too, does this log appear to be), so I re-ran the test, and as you probably suspected, I think there’s a little more at play.

I was able to navigate through a couple of way points.

It approached each one very slowly, but this time it did make it past the first waypoint.

I also made up a new mission that largely steers clear of my fences, and that went just fine.

But when I run a mission that works fine in 4.2.3 but now on 4.4.0-beta1, at least the first few waypoints it struggles because of the nearby fence - it slows down, approaches slowly, creeps forward, and then ultimately concludes there’s no path forward (or to the waypoint) and stops.

24 5-31-2023 7-22-14 PM.zip (138.4 KB)

It looks like these logs didn’t pan out, either - and I enabled additional logging detail, and disarmed logging.

Assuming they’re blank, like I think, I’ll try again tomorrow. :wink:

Edit: corrupt SD card. Time for a new one.

SusanMower05312023_Rover440beta1_morelogging.param (15.2 KB)
SusanMower05312023_Rover423_morelog.param (15.2 KB)

2023-06-01 19-26-50.zip (291.7 KB)
2023-06-01 19-34-21.zip (674.3 KB)

182710
184040
185852
192650
193421
193609
195207

These logs look better. It should be a 4.4.0-beta1 (18-27-10) and then reverting to 4.2.3 (18-40-40) and then back to 4.4.0 beta1 (18-58-52)

Running the same mission, similar conditions, etc.

I did get past the first and even second waypoint a few times.

4.2.3 is more aggressive in route running - it accelerates to cruise, and doesn’t slow down much as it comes to the WP and turns. I’ve modified the mission over time to make sure the rover can reach the waypoints without breaking the fence, and usually on 4.2.3 it does so.

4.4.0 is much smoother overall, and as it approaches the WP - and more critically, the fence next to it - it slows down to a crawl. Sometimes it’ll reach the WP, sometimes not. A few times, toggling in and out of auto caused it to re-assess the options and it would find a path to take.

Edit:
And seeing some of the other testing posts - I most definitely did not do any retuning after the upgrade, so there could be all sorts of things worng/off - I must have missed a key step in the upgrade process.