Copter-4.2.0 has been released!

Copter-4.2.0 has been released as the official/stable version and can be downloaded and installed using MP or QGC (or you can manually download the .apj file from firmware.ardupilot.org)

Because of the built-in parameter upgrade feature, there should be no need to backup and restore your parameters as part of the upgrade. If you find you later need to revert to 4.1.x, please use MP’s Install Firmware screen’s “All Options” link or manually download the 4.1.x binary from firmware.ardupilot.org.

Warnings:

  • Some setups using BLHeli_S ESCs may not arm or spin. If you notice problems with BLHeli_S ESCs please revert to 4.1.5 and wait for 4.2.1 which we hope will resolve these issues.
  • Telemetry radios that do not understand MAVLink2 may fail to work unless SERIALx_PROTOCOL is set to “1”.
  • If GPIO pins (used may be used for buttons, camera triggers, relays, etc) do not work, the issue is likely that the appropriate SERVOx_FUNCTION parameter must be set to -1. Please see this wiki page for more details.
  • Precision landing may change the vehicle’s heading if it loses sight of the target and repositions itself. These “retries” can be disabled by setting PLND_RET_MAX = 0

The long list of changes vs 4.1.5 are in the ReleaseNotes and copied below. For those who were involved with beta testing, this version is exactly the same as the last release candidate (-rc4).

  1. AHRS/EKF improvements
    a) EKF startup messages reduced
    b) GPS<->Opticalflow automatic switching improved (see ahrs-source-gps-optflow.lua script)
    c) LORD Microstrain CX5/GX5 external AHRS support
    d) ModalAI VOXL non-GPS system supported (set VISO_TYPE=3, uses ODOMETRY mavlink msg)
  2. Control and flight mode enhancements
    a) Acro max rate params renamed and improved (see ACRO_RP_RATE, ACRO_Y_RATE, PILOT_Y_RATE, PILOT_Y_EXPO)
    b) Airmode NOT enabled when arming with switch (see ACRO_OPTIONS and “ArmDisarm with AirMode” RCx_OPTION)
    c) Auto and Guided support pausing (uses DO_PAUSE_CONTINUE mavlink command)
    d) Auto supports up to 100 DO_JUMP commands on high memory boards
    e) Autotune reporting improved (less spam, prints final tune)
    f) Delay removed when waypoints are very close together
    g) FLIGHT_OPTIONS to release gripper on thrust loss
    h) Follow mode supports FOLLOW_TARGET message
    i) ForceFlying auxiliary switch allows pilot to disable land-detector
    j) Guided mode acceleration target support
    k) Guided mode logging of targets improved (GUID msg split into GUIP, GUIA)
    l) Harmonic notch filter on more than four motors
    m) Land mode pilot controlled repositioning max speed reduced (also affects RTL and Auto)
    n) Loiter mode ignores ATC_SLEW_YAW parameter
    o) Pause and continue support (GCS changes are still pending)
    p) Precision landing improvements esp when using PLAND_EST_TYPE = 1/KalmanFilter
    q) RTL’s safe altitude (RTL_ALT) increased 85km (was 325m)
    r) Simple mode heading reset via auxiliary switch
    s) Sport mode deprecated
    t) SURFTRAK_MODE allows disabling surface tracking in Loiter, AltHold, etc
    u) Turtle mode (allows righting a copter while on the ground)
    v) Waypoint navigation will make use of maximum waypoint radius to maximize speed through corners
  3. Custom build server support (see https://custom.ardupilot.org)
  4. Lua scripting improvements
    a) ahrs::get_location replaces get_position (get_position still works for now)
    b) Auto support for NAV_SCRIPT_TIME commands (Lua within Auto)
    c) Frame string support (allows scripting based frame to display custom description after startup)
    d) Parameter support (no need to always use SCR_USERx)
    e) Servo output control by channel number (previously was only possibly by specifying the SERVOn_FUNCTION value)
    f) Scripting heap size increased to 100k on F7/H7
    g) Script logged to onboard log (can be disabled by setting SCR_DEBUG_OPTS)
  5. New autopilots supported
    a) AirLink
    b) BeastF7v2, BeastH7v2
    c) FlyingMoon F407 and F427
    d) JHEMCU GSF405A
    e) KakuteH7, KakuteH7Mini
    f) MambaF405US-I2C
    g) MatekF405-TE
    h) Matek F765-Wing-bdshot
    i) ModalAI fc-v1
    j) PixC4-Jetson
    k) Pixhawk5X
    l) QioTekZealotH743
    m) RPI-Zero2W
    n) SPRacingH7 Extreme
    o) Swan-K1
  6. Safety improvements
    a) Button, Relay and RPM GPIO pin conflict pre-arm check improved
    b) Dijkstra’s avoidance performance improvements including converting to A*
    c) Motor PWM range always uses MOT_PWM_MIN/MAX (if these are not set, they are defaulted to RC3_MIN/MAX values)
    d) Parachute option to leave servo in open position (see CHUTE_OPTIONS parameter)
    e) Parachute released arming check added
    f) Pre-arm check of IMU heater temp
    g) Pre-arm check of rangefinder health
    h) Pre-arm check of throttle position skipped if PILOT_THR_BHV is “Feedback from mid stick”
  7. Sensor driver enhancements
    a) ADIS16470, ADIS16507 and BMI270 IMU support
    b) Airspeed sensor support (reporting only, not used for estimation or control)
    c) AK09918 compass support
    d) Battery monitor supports voltage offset (see BATTx_VLT_OFFSET)
    e) BATT_OPTIONS supports sending resting voltage
    f) Benewake TFMiniPlus I2C address defaults correctly
    g) Buzzer can be connected to any GPIO on any board
    h) Compass calibration (in-flight) uses GSF for better accuracy
    i) CRSFv3 support, CSRF telemetry link reports link quality in RSSI
    j) Custom compass orientation for DroneCAN compasses
    k) Cybot D1 Lidar
    l) DroneCan (aka UAVCAN) battery monitors support scaling (see BATTx_CURR_MULT)
    m) DroneCan (aka UAVCAN) GPS-for-yaw support
    n) DShot uses narrower bitwidths for more accurate timing (allows BLHeli BlueJay to work)
    o) Electronic Fuel Injection support incl Lutan EFI
    p) FETtecOneWire resyncs if EMI causes lost bytes
    q) IMU heater params renamed to BRD_HEAT_xxx
    r) INS_NOTCH parameters renamed to INS_HNTC2
    s) Landing gear enable parameter added (see LGR_ENABLE)
    t) Lightware SF40C ver 0.9 support removed (ver 1.0 and higher still supported)
    u) Matek H743 supports ICM42688
    v) Maxbotix serial sonar driver support RNGFNDx_SCALING parameter to support for varieties of sensor
    w) MPPT solar charge controller support
    x) MTK GPS driver removed
    y) Optical flow in-flight calibration
    z) Ping200x support
    aa) Proximity sensor min and max range (see PRX_MIN, PRX_MAX)
    ab) QSPI external flash support
    ac) uLanding (aka USD1) radar provides average of last few samples
    ad) bUnicore NMEA GPS support for yaw and 3D velocity
  8. TradHeli enhancements
    a) Attitude control default gains improved
    - ATC_RAT_RLL_FF, _I, _IMAX, _ILMI, _FLTT
    - ATC_RAT_PIT_FF, _I, _IMAX, _ILMI, _FLTT
    - ATC_RAT_YAW_IMAX, _FLTT
    b) AutoTune mode
    c) Collective setup (users will be forced to setup new collective parameters)
    d) Rotor Speed Controller Internal Governor improvements (users required to retune governor)
    e) Rotor Speed Controller Cooldown timer added for ICE and turbine engines
    f) _VFF params renamed to _FF
  9. Other System enhancements
    a) Board ID sent in AUTOPILOT_VERSION mavlink message
    b) Compass calibration stick gestures removed
    c) DO_SET_CAM_TRIG_DIST supports instantly triggering camera
    d) DJI FPV OSD multi screen and stats support
    e) GPIO pins configured by setting SERVOx_FUNCTION to -1 (also see SERVO_GPIO_MASK. BRD_PWM_COUNT removed)
    f) GPIO pin support on main outputs on boards with IOMCU
    g) GyroFlow logging (see LOG_BITMASK’s “VideoStabilization” option)
    h) Firmware version logged in VER message
    i) Log and monitor threads stack size increased
    j) SD card format via MAVLink
    k) Serial port option to disable changes to stream rate (see SERIALx_OPTIONS)
    l) VIBE logging units to m/s/s
    m) Vibration failsafe disabled in manual modes
  10. Bug fixes
    a) Arming checks ignore SERVOx_MIN, MAX if setup as GPIO pin
    b) Auto and Guided mode takeoff alt fixed if taking off from below home or frame set to absolute (aka AMSL)
    c) Auto mode CONDITION_YAW command completion fix
    d) Auto mode infinite loop with nav commands that fail to start fixed
    e) AutoTune disables ATC_RAT_xxx_SMAX during twitch (SMAX may limit gains to reduce oscillation)
    f) Battery remaining percentage fixed when using Sum battery
    g) BeastH7v2 BMI270 baro support
    h) Blended Z axis accel calculation fix when not using first IMU
    i) BLHeli passthrough reliability improvements
    j) Compass learning (inflight) fixed to ignore unused compasses (e.g. those with COMPASS_USE = 0)
    k) DShot reversal bug with IOMCU based boards (see SERVO_BLH_RVMASK)
    l) EKF optical flow terrain alt reset fixed (large changes in rangefinder alt might never be fused)
    m) EKF resets due to bad IMU data occur at most once per second
    n) EKF3 accel bias fixed when an IMU is disabled
    o) EKF3 variance constraint fix used to prevent “ill-conditioning”
    p) GPIO pin fix on CubeOrange, F4BY, mRoControlZeroF7, R9Pilot
    q) GPS blending fix that could have resulted in the wrong GPS being used for a short time
    r) Guided mode yaw rate timeout fix (vehicle could keep yawing even if companion computer stopped sending target)
    s) Log file list with over 500 logs fixed
    t) MAVlink2 serial ports always send MAVLink2 messages (previously waited until other side sent MAVLink2)
    u) Motor Test, Turtle mode respect emergency stop switch
    v) Omnibusf4pro bi-directional dshot fix
    w) PosHold braking fix if SCHED_LOOP_RATE set to non-default value
    x) POWR log message MCU voltage fix (min and max voltage were swapped)
    y) Precision landing in RTL activates even if pilot had earlier deactivated by repositioning in Land
    z) Proximity sensor fix when using MAVLink lidars in non-forward orientations
    aa) RC handover between IOMCU RC input and a secondary RC input on a serial port fixed
    ab) Real-Time-Clock (RTC) oldest possible date updated to Jan-2022
    ac) RPM sensor fix to avoid “failed to attach pin” spam to GCS
    ad) SPRacingH7 firmware install fix
    ae) STM32 DMA fatal exceptions disabled (caused watch dogs reboots with zero information)
    af) Terrain reference adjustment ensures alt-above-terrain is zero at takeoff (see TERRAIN_OFS_MAX)
    ag) Tricopter, Coax copter fin trim fix when using DShot/BLheli

Thanks very much to everyone who participated in the beta release and to the many developers who contributed to this release!

18 Likes

was testing copter-4.2.0 on SITL, found one change in behaviour with the navigation commands in guided mode, when i am keep sending the copter to multiple locations in guided mode using set_target_location and then in between when i am sending yaw command for changing the heading of the copter one time then this command is getting override by the set_target_location command and vehicle is not able to change the heading after that, that was not the case with Copter-4.0.7

@Notorious7,

I’m not sure if it will help but there is a GUID_OPTION parameter that allows specifying whether SCurves or the simpler position controller are used. Maybe try setting or unsetting one of the bits. Sorry to be vague.

Hi, I have been experiencing some problems with the EKF3 origin when using positioning with UWB beacons. The last tests I have performed were using AC 4.2.0 and this problem persists. I think it could be a bug, if someone could take a look at it, I would appreciate it.

I leave a link to the post where I discuss this issue: 85037 EKF3-large-position-offset-after-startup-using-uwb-beacons

Can someone point me in the right direction to perform something like motor remapping?
I am running a x8, of which I thought just changing servo outputs would be sufficient, but it seems it is not making any sense with dshot 300 escs…

sorry if wrong place.

EDIT, fixed it, just think the servo mapping section of mission planner is far from clear and concise, but after drawing out my mapping, and fidgeting for 4 hours over 2 different days, It is mapped correctly.

1 Like

Thanks for the update!

This might be a dumb question, if I upgrade to 4.2.0 from 4.1.5 will I have to recalibrate sensors, radio, re-trim, re-auto tune, etc my Hexa?

You should not have to

1 Like

Gread work, will test next week.

1 Like

Thanks for the new release! Question about the ModalAI VOXL support. Does that mean that Arducopter is now supported by the Voxl2 built in flightcontroller?
The Voxl2 specs list PX4 only.
Is there any documentation available to use the Voxl module along with Arducopter?

Hi @mtbsteve,

VOXL1 is supported but VOXL2 support hasn’t been implemented yet. We’ve discussed with ModalAI though (they’re a Partner now) and we hope to begin work on the port in a few weeks. Because the autopilot doesn’t use ChibiOS it’s a much bigger piece of work than a normal port.

@rmackay9
I have flown copter with latest 4.2.0 firmware i have set LAND_HIGH_ALT = 150 cm/s
Also WP_ SPEED_ DOWN = 150 cm/s

But when landing phase always decent at 0.5m/s only even i have set 1.5m/s becasue of this changes?

I just updated a PIxracer R15 to 4.2 and my ESCs started beeping non-stop. I could arm the quad but the motors wouldn’t turn, and motor test wouldn’t work. (this is a fully configured and flying quad. In fact it was flying earlier today). I tried to recalibrate the ESCs but that had no change.

I tracked it down to the MOT_PWM_MIN value being 0. I saw this and checked the RC3_MIN value. I found that set to 983, and _MAX is 2005. MOT_PWM_MAX is 2000. I manually set MOT_PWM_MIN to 1100 and everything seems to be working. I haven’t flown it yet, but the motor test works and when I arm it the motors respond as normal.

kalai,
What LAND parameters do you have?
Maybe post a .bin log file of this happening, we can see all the parameters also.

For example:
LAND_ALT_LOW,700
LAND_SPEED,40
LAND_SPEED_HIGH,140

At the LAND_ALT_LOW (7 meters in this case) the descent rate will switch from LAND_SPEED_HIGH 140cm/s to LAND_SPEED 40cm/s

HI @Allister,

Thanks for the report. Is it possible that MOT_PWM_MIN was manually set to zero somehow? Maybe the param file from a previous version was loaded? If this was done then the defaulting of MOT_PWM_MIN to the RC3_MIN value would be overwritten.

Of course arming checks were enabled? I think you’ve found at least one issue which is that we should add a pre-arm check that MOT_PWM_MIN and MAX are non-zero. At the moment we only check that MOT_PWM_MAX > MOT_PWM_MIN… but we don’t check if MOT_PWM_MIN is non-zero…

I don’t think I’ve ever adjusted MOT_PWM_MIN. Of course I can’t be 100% sure of that over the year+ this quad has been flying, but I can’t think of when or why I would have touched that one. This quad has basic PWM ESCs and there were no setup issues with the ESCs that would have had me messing with settings.

All Arming checks are active (set to 1).

In case it matters, I migrated this one from 4.1.3.

1 Like

Thank you for your responce.
i have set LAND_ALT_LOW = 2000
LAND_SPEED = 50
LAND_SPEED_ HIGH = 150

but this is not happening. Here is the log https://drive.google.com/file/d/1U-686xZGv4f_w64EXYLXYmHvS8M8sQco/view?usp=sharing

i have been facing another issues also that i never faced before.

Issue 1 : Auto disarm not happening
Ex; i have flown full autonomous flight from takeoff to land .
everything happened as expected but after touchdown the ground its does not disarm itself (Disarm Delay = 6 s) after 6sec also its keep rotating its only disarm when i switch to stabilize mode from my RC and YAW left to disarm Manually…in Loiter mode also its not disarming with LOW THROTTLE LEFT YAW. i have well calibrated Rc transmitter and done ESC semi automatic Calibration too ESC CALIBATION SET to 3 .
Used model is T.drone M690A

As @ Allister reported here i had same issue with beeping as signal is not received by ESC.
After that i have set
MOT_PWM_MIN = 1100
MOT_PWM_MAX = 1940

then issue solved and also given motor test command set THR value to 10 and all motors working Normally.

ISSUE 2 : in ALTHOLD or LOITER mode its doesn’t maintain the height as when throttle stick is centered .either its goes keep altitude high or keep descending as low.

EX : flying in Stabilize mode while takeoff and switch to Alt hold with throttle stick centered( using Skydroid T12 transmitter which is Spring centered stick) after changed to ALTHOLD or LOITER mode either its keep increasing height or dropping in alt .To solve this issue( height climbing ) i have to keep THR stick to below center position and leave it in center stick position to stop height climbing.
for descending i have to do vice versa.

SET PILOT_THR_BEHAVIOUR = 7 but NO improvement.

then i just downgraded the AC 4.2.0 to AC 4.1.5 but still issue continues.
here is the 4.1.5 with same issue .

https://drive.google.com/file/d/1e3MhfCUmRXReh51K9Dh3A37w57bKKheR/view?usp=sharing

The quad is in Auto the whole time, it doesnt change into Land or RTL mode, so it’s just following whatever settings you have in the mission.
I’m not sure about where it’s getting the descent rate from though.

There’s some battery settings missing that I would definitely have in place.
Get current monitoring working properly.

Vibrations are a bit high, I’d try to improve that, then enable HNOTCH properly and run Autotune.
Even though it’s flying OK now, this will help a lot and also reduce battery usage.

Test Land and RTL outside a mission and check what happens.

I have been flown arducopter many years and never had this kind of issue.my previous quad also we flown Fully auto flight when landing phase it was definitely followed either WPNAV_SPEED_DN or LAND_ALT_HIGH parameter while landing or descending any of the mode.

I have already tested each individual mode as you said here .but all mode response is same as described.

Kindly check 4.1.5 log also for land command mode decent rate checked but its was not exceed 0.5m/s