You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
963 lines
41 KiB
963 lines
41 KiB
Rover Release Notes: |
|
-------------------------------- |
|
Rover 3.5.1 17-May-2019 / 3.5.1-rc1 30-Apr-2019 |
|
Changes from 3.5.0 |
|
1) WHEEL_DISTANCE mavlink messages sent to ground station and companion computers |
|
2) Bug fixes: |
|
a) EKF compass switching fix for vehicles with 3 compasses |
|
b) Guided's heading-and-speed controller no longer uses land based speed control |
|
c) Pre-arm check fix that all required motors for the frame are configured |
|
d) Prevent loss of active IMU from causing loss of attitude control |
|
e) Added startup check for Hex CubeBlack sensor failure |
|
f) don't reset INS_ENABLE_MASK based on found IMUs |
|
-------------------------------- |
|
Rover 3.5.0 06-Feb-2019 |
|
Changes from 3.5.0-rc3 |
|
1) Bug fixes and minor enhancements |
|
a) Avoid potential divide-by-zero when waypoints are almost in a straight line |
|
b) LOIT_TYPE parameter description fix |
|
-------------------------------- |
|
Rover 3.5.0-rc3 30-Jan-2019 |
|
Changes from 3.5.0-rc2 |
|
1) Fix build issue affecting fmuv2 |
|
-------------------------------- |
|
Rover 3.5.0-rc2 24-Jan-2019 |
|
Changes from 3.5.0-rc1 |
|
1) ChibiOS fixes and enhancements to many boards including Pixhawk4 |
|
2) EKF failsafe added and checked before entering autonomous modes |
|
3) Object avoidance enabled in autonomous modes (Auto, Guided, RTL) |
|
4) Cruise speed/throttle learning always runs for 2 seconds (saves user from having to lower switch) |
|
5) Boats hold position after reaching target in Auto and Guided (also see MIS_DONE_BEHAVE) |
|
6) MAVLink message interval support (allows precise control of mavlink message update rates) |
|
7) Bug fixes and minor enhancements: |
|
a) DShot ESC support |
|
b) Auxiliary switch 7 parameter copy from CH7_OPTION to RC7_OPTION |
|
c) Wheel encoder offset fix |
|
d) SmartRTL default num points increased to 300 |
|
-------------------------------- |
|
Rover 3.5.0-rc1 12-Nov-2018 |
|
Changes from 3.4.2: |
|
1) ChibiOS provides improved performance and support for many new boards including: |
|
a) F4BY |
|
b) TauLabs Sparky2 |
|
c) Furious FPV F-35 lightening and Wing FC-10 |
|
d) Holybro KakuteF4 |
|
e) Mateksys F405-Wing |
|
f) Omnibus F4 Pro, NanoV6 and F7 |
|
g) SpeedyBee F4 |
|
2) BalanceBot support |
|
3) Sailboat support |
|
4) OmniPlus, OmniX frame support (vehicles can move laterally using 4 thrusters or wheels) |
|
5) Auxiliary Switches expanded to many channels (see RCx_OPTION parameters) |
|
6) External position estimates accepted from ROS and Vicon systems |
|
7) Mode changes: |
|
a) Follow mode (allows following another vehicle if connected via telemetry) |
|
b) Simple mode (pilot controls direction regardless of vehicle's heading) |
|
c) Loiter can be configured to always drive towards target (i.e. does not reverse) (see LOIT_TYPE parameter) |
|
d) Guided, RTL, SmartRTL will reverse towards target if DO_SET_REVERSE command received (via telemetry or as mission command) |
|
8) Bug fixes and small enhancements: |
|
a) RC and GCS failsafe timeout shortened |
|
b) Object avoidance fix to include all sectors from proximity sensor (aka 360 lidar) |
|
c) Safety switch ability to arm/disarm vehicle now configurable (see BRD_SAFETYOPTION parameter) |
|
d) Onboard OSD support (for ChibiOS-only boards) |
|
e) Gripper support |
|
f) Sprayer support |
|
-------------------------------- |
|
Rover 3.4.2 30-Jul-2018 / 3.4.2-rc1 23-Jul-2018 |
|
Changes from 3.4.1: |
|
1) bug fix to pivot turn logic during missions |
|
2) dataflash logging improvement to NTUN message |
|
-------------------------------- |
|
Rover 3.4.1 04-Jul-2018 / 3.4.1-rc1 12-Jun-2018 |
|
Changes from 3.4.0: |
|
1) lane based speed control (vehicle slows to stay close to line between waypoints), WP_OVERSHOOT replaces SPEED_TURN_GAIN |
|
2) MOT_SPD_SCA_BASE allow configuring speed above which speed scaling begins |
|
3) disable acceleration limits when ATC_ACCEL_MAX is zero |
|
4) accept DO_CHANGE_SPEED commands in Auto, Guided, RTL, SmartRTL |
|
5) DPTH dataflash log messages for recording downward facing echosounders on boats |
|
-------------------------------- |
|
Rover 3.4.0 12-Jun-2018 / 3.4.0-rc1 01-Jun-2018 |
|
Changes from 3.3.1-rc2: |
|
1) Loiter mode for boats |
|
2) Omni rover support (three wheeled rover with lateral movement) |
|
3) vision-position-estimate support for use with ROS |
|
4) Control improvements: |
|
a) reversing control improvements |
|
b) ATC_DECEL_MAX allows deceleration to be faster or slower than acceleration |
|
c) PIVOT_TURN_RATE allows slower pivot turns |
|
d) turn-rate I-term reset when switching in from manual modes |
|
5) NMEA Echosounder support for underwater depth monitoring |
|
6) Bug fixes: |
|
a) fix forward/back acceleration limiting |
|
b) MaxsonarI2C driver fix |
|
-------------------------------- |
|
Rover 3.3.1-rc2 12-May-2018 |
|
Changes from 3.3.1-rc1: |
|
1) Bug fix use of ATC_STR_RAT_MAX to limit maximum turn rate |
|
-------------------------------- |
|
Rover V3.3.1-rc1 09-May-2018 |
|
Changes from 3.3.0: |
|
1) Vectored Thrust to improve attitude control for boats with rotating motors |
|
2) minor changes and bug fixes: |
|
a) remove jump forward when transitioning from forward to reverse |
|
b) safety switch allows disarming motors (was disabled in 3.3.0) |
|
-------------------------------- |
|
Rover V3.3.0 07-May-2018 |
|
Changes from 3.3.0-rc1: |
|
1) default parameter changes |
|
a) TURN_MAX_G reduced from 1.0 to 0.6 |
|
b) ATC_STR_ANG_P increased from 1.0 to 2.5 (converts angle error to desired turn rate during pivot turns) |
|
c) ATC_STR_ACC_MAX reduced from 360 to 180 deg/s/s (slows acceleration in pivot turns) |
|
-------------------------------- |
|
Rover V3.3.0-rc1 19-Apr-2018 |
|
Changes from 3.2.3: |
|
1) Simple object avoidance support |
|
2) Circular and polygon fence support |
|
3) Pivot turn improvements |
|
a) Heading control used to aim at new target |
|
b) ATC_STR_ACC_MAX limits maximum rotational acceleration |
|
c) ATC_STR_RAT_MAX limits maximum rotation rate |
|
4) Allow ACRO mode without GPS for skid-steering vehicles (reverts to manual throttle) |
|
5) MOT_THR_MIN used as deadzone |
|
6) Parameter default changes: |
|
a) PIVOT_TURN_ANGLE default raised from 30 to 60 degrees |
|
b) ATC_STR_RAT_P and I reduced to 0.2 |
|
c) ATC_STR_RAT_FILT and ATC_SPEED_FILT reduced from 50hz to 10hz to better match vehicle response time |
|
7) Boats report themselves as boats allowing ground stations to display boat icon on map |
|
8) ChibiOS support |
|
-------------------------------- |
|
Rover V3.2.3 09-Apr-2018 / V3.2.3-rc1/rc2 02-Apr-2018 |
|
Changes from 3.2.2: |
|
1) Waypoint origin uses previous waypoint or vehicle stopping point |
|
2) Boats send correct mav-type to ground station |
|
3) TURN_MAX_G parameter description updates (allows lower values) |
|
4) fix two-paddle input decoding |
|
-------------------------------- |
|
Rover V3.2.2 19-Mar-2018 / V3.2.2-rc1 08-Mar-2018 |
|
Changes from 3.2.1: |
|
1) Fix loss of steering control when stopping in Acro and Steering modes |
|
-------------------------------- |
|
APM:Rover V3.2.1 29-Jan-2018 / V3.2.1-rc1 24-Jan-2018 |
|
Changes from 3.2.0: |
|
1) Fix mode switch logic to allow Auto, Guided, RTL, SmartRTL, Steering, Acro using non-GPS navigation (i.e. wheel encoders, visual odometry) |
|
-------------------------------- |
|
APM:Rover V3.2.0 13-Jan-2018 |
|
Changes from 3.2.0-rc4: |
|
1) Here GPS/compass default orientation fix (ICM20948) |
|
2) PID values sent to ground station regardless of mode (see GCS_PID_MASK parameter) |
|
3) Steering PID min and max ranges expanded |
|
4) Mavlink message definition update |
|
-------------------------------- |
|
APM:Rover V3.2.0-rc4 05-Jan-2018 |
|
Changes from 3.2.0-rc3: |
|
1) Steering controller supports feed-forward (reduces wobble) |
|
2) WP_SPEED, RTL_SPEED parameters allow speed independent of CRUISE_SPEED |
|
3) Dataflash logging improvements for steering and throttle |
|
4) Remove auto-trim at startup |
|
5) GPS reports healthy even without 3d lock |
|
--------------------------------- |
|
APM:Rover V3.2.0-rc3 05-Dec-2017 |
|
Changes from 3.2.0-rc2: |
|
1) SmartRTL mode (retraces path back to home) |
|
2) Acro mode (pilot controls speed and turn rate) |
|
3) Guided mode ROS integration fixes |
|
4) Steering mode allows pivot turns |
|
5) Auto mode pivots on sharp corners |
|
6) Aux switch allows arming/disarming and mode change |
|
7) PILOT_STEER_TYPE parameter allows controlling turn direction when backing up |
|
8) Mixer change to allow steering to use full motor range (removes need for MOT_SKID_FRIC) |
|
--------------------------------- |
|
APM:Rover V3.2.0-rc2 28-Oct-2017 |
|
Changes from 3.2.0-rc1: |
|
1) MOT_SKID_FRIC parameter allows increasing power for skid-steer vehicle pivot-turns |
|
2) Bug Fixes: |
|
a) speed nudging fix in AUTO mode |
|
b) throttle slew range fix (was slightly incorrect when output range was not 1100 ~ 1900) |
|
c) PID desired and achieved reported to GCS when GCS_PID_MASK param set to non-zero value |
|
d) use-pivot fix to use absolute angle error |
|
--------------------------------- |
|
APM:Rover V3.2.0-rc1 25-Aug-2017 |
|
Changes from 3.1.2: |
|
1) Skid-steering vehicle support added (i.e. tank track or R2D2 style vehicles) |
|
2) Brushless motor support |
|
3) Improved speed/throttle and steering controllers: |
|
a) layered P and PID controllers with optional feedforward, input filtering and saturation handling (reduces unnecessary I-term build-up) |
|
b) forward-back acceleration limited (see ATC_ACCEL_MAX parameter) |
|
c) pro-active slowing before waypoint in order to keep overshoot at or below WP_OVERSHOOT distance |
|
d) proper output scaling for skid-steering vs regular car steering controls |
|
e) TURN_RADIUS parameter added to allow better control of turn in Steering mode |
|
f) speed along forward-back axis used instead of total ground speed (resolves unusual behaviour for boats being washed downstream) |
|
4) Auxiliary switch changes (see CH7_OPTION parameter): |
|
a) "Save Waypoint" saves the current location as a waypoint in all modes except AUTO if the vehicle is armed. If disarmed the mission is cleared and home is set to the current location. |
|
b) "Learn Cruise" sets the THROTTLE_CRUISE and SPEED_CRUISE parameter values to the vehicle's current speed and throttle level |
|
5) Wheel encoder supported for non-GPS navigation (can also be used with GPS) |
|
6) Visual Odometry support for non-GPS navigation (can also be used with GPS) |
|
7) Guided mode improvements: |
|
a) for SET_ATTITUDE_TARGET accepts quaternions for target heading, valid thrust changed to -1 ~ +1 range (was previously 0 ~ 1) |
|
b) COMMAND_LONG.SET_YAW_SPEED support fixes (thrust field accepted as target speed in m/s) |
|
c) SET_POSITION_TARGET_GLOBAL_INT, _LOCAL_NED fixes and added support for yaw and yaw-rate fields |
|
8) Bug Fixes: |
|
a) resolve occasional start of motors after power-on |
|
b) steering mode turn direction fix while reversing |
|
c) reversing in auto mode fixes (see DO_REVERSE mission command) |
|
---------------------------------------------------------- |
|
Release 3.1.2, 15 March 2017 |
|
============================ |
|
Minor bugfix release. |
|
|
|
- Crashing detection is off by default |
|
- DISARMing of a rover via the transmitter stick works again |
|
- If a user was driving in reverse in Manual and went into an AUTO |
|
mode the rover would do the mission in reverse. This is fixed. |
|
|
|
|
|
Release 3.1.1, 31 January 2017 |
|
============================== |
|
Minor bugfix release for a crash bug in the SRXL driver |
|
|
|
|
|
Release 3.1.0, 22 December 2016 |
|
=============================== |
|
The ArduPilot development team is proud to announce the release of |
|
version 3.1.0 of APM:Rover. This is a major release with a lot of |
|
changes so please read the notes carefully! |
|
|
|
A huge thanks to ALL the ArduPilot developers. The Rover code |
|
benefits tremendously from all the hard work that goes into the Copter |
|
and Plane vehicle code. Most of the code changes in this |
|
release were not specifically for Rover however because of the |
|
fantastic architecture of the ArduPilot code Rover automatically gets |
|
those enhancements anyway. |
|
|
|
Note that the documentation hasn't yet caught up with all the changes |
|
in this release. We are still working on that, but meanwhile if you |
|
see a feature that interests you and it isn't documented yet then |
|
please ask. |
|
|
|
The PX4-v2 build has had CANBUS support removed due to firmware size |
|
issues. If Rover users want CANBUS support you will need to install |
|
the PX4-v3 build located in the firmware folder here: |
|
http://firmware.ap.ardupilot.org/Rover/stable/PX4/ |
|
|
|
EKF1 has been removed as EKF2 has been the long term default and is |
|
working extremely well and this has allowed room for EKF3. |
|
|
|
EKF3 is included in this release but it is not the default. Should |
|
you want to experiment with it set the following parameters: |
|
AHRS_EKF_TYPE=3 |
|
EK3_ENABLE=1 |
|
but note it is still experimental and you must fully understand the |
|
implications. |
|
|
|
New GUIDED Command |
|
------------------ |
|
Rover now accepts a new message MAV_CMD_NAV_SET_YAW_SPEED which has an |
|
angle in centidegrees and a speed scale and the rover will drive based |
|
on these inputs. |
|
|
|
The ArduPilot team would like to thank EnRoute for the sponsoring of |
|
this feature |
|
http://enroute.co.jp/ |
|
|
|
COMMAND_INT and ROI Commands |
|
---------------------------- |
|
COMMAND_INT support has been added to Rover. This has allowed the |
|
implementation of SET_POSITION_TARGET_GLOBAL_INT, |
|
SET_POSITION_TARGET_LOCAL_NED and DO_SET_ROI as a COMMAND_INT |
|
|
|
The ArduPilot team would like to thank EnRoute for the sponsoring of |
|
this feature |
|
http://enroute.co.jp/ |
|
|
|
Reverse |
|
------- |
|
Its now possible in a mission to tell the rover to drive in |
|
Reverse. If using Mission Planner insert a new Waypoint using "Add |
|
Below" button on the Flight Plan screen and select from the Command |
|
drop down list you will see a new command "DO_SET_REVERSE". It takes 1 |
|
parameter - 0 for forward, 1 for reverse. It's that simple. Please give |
|
it a try and report back any success or issues found or any questions |
|
as well. |
|
|
|
The ArduPilot team would like to thank the Institute for Intelligent |
|
Systems Research at Deakin University |
|
(http://www.deakin.edu.au/research/iisri16) for the sponsoring of the |
|
reverse functionality. |
|
|
|
Loiter |
|
------ |
|
This changes brings the LOITER commands in line with other ArduPilot |
|
vehicles so both NAV_LOITER_UNLIM and NAV_LOITER_TIME are supported and are |
|
actively loitering. This means for instance if you have set a boat to |
|
loiter at a particular position and the water current pushes the boat off |
|
that position once the boat has drifted further then the WP_RADIUS |
|
parameter distance setting from the position the motor(s) will be |
|
engaged and the boat will return to the loiter position. |
|
|
|
The ArduPilot team would like to thanko MarineTech for sponsoring this |
|
enhancement. |
|
http://www.marinetech.fr |
|
|
|
Note: if you currently use Param1 of a NAV_WAYPOINT to loiter at a |
|
waypoint this functionality has not changed and is NOT actively loitering. |
|
|
|
Crash Check |
|
----------- |
|
Rover can now detect a crash in most circumstances - thanks Pierre |
|
Kancir. It is enabled by default and will change the vehicle into HOLD |
|
mode if a crash is detected. FS_CRASH_CHECK is the parameter used to |
|
control what action to take on a crash detection and it supports |
|
0:Disabled, 1:HOLD, 2:HoldAndDisarm |
|
|
|
Pixhawk2 heated IMU support |
|
--------------------------- |
|
This release adds support for the IMU heater in the Pixhawk2, |
|
allowing for more stable IMU temperatures. The Pixhawk2 is |
|
automatically detected and the heater enabled at boot, with the target |
|
IMU temperature controllable via BRD_IMU_TARGTEMP. |
|
Using an IMU heater should improve IMU stability in environments with |
|
significant temperature changes. |
|
|
|
PH2SLIM Support |
|
--------------- |
|
This release adds support for the PH2SLIM variant of the Pixhawk2, |
|
which is a Pixhawk2 cube without the isolated sensor top board. This |
|
makes for a very compact autopilot for small aircraft. To enable |
|
PH2SLIM support set the BRD_TYPE parameter to 6 using a GCS connected |
|
on USB. |
|
|
|
AP_Module Support |
|
----------------- |
|
This is the first release of ArduPilot with loadable module support |
|
for Linux based boards. The AP_Module system allows for externally |
|
compiled modules to access sensor data from ArduPilot controlled |
|
sensors. The initial AP_Module support is aimed at vendors integrating |
|
high-rate digital image stabilisation using IMU data, but it is |
|
expected this will be expanded to other use cases in future releases. |
|
|
|
Major VRBrain Support Update |
|
---------------------------- |
|
This release includes a major merge of support for the VRBrain family |
|
of autopilots. Many thanks to the great work by Luke Mike in putting |
|
together this merge! |
|
|
|
Much Faster Boot Time |
|
--------------------- |
|
Boot times on Pixhawk are now much faster due to a restructuring of |
|
the driver startup code, with slow starting drivers not started unless |
|
they are enabled with the appropriate parameters. The restructuring |
|
also allows for support of a wide variety of board types, including |
|
the PH2SLIM above. |
|
|
|
This release includes many other updates right across the flight |
|
stack, including several new features. Some of the changes include: |
|
|
|
- log all rally points on startup |
|
- the armed state is now logged |
|
- support added for MAV_CMD_ACCELCAL_VEHICLE_POS |
|
- support MAVLink based external GPS device |
|
- support LED_CONTROL MAVLink message |
|
- support PLAY_TUNE MAVLink message |
|
- added AP_Button support for remote button input reporting |
|
- support 16 channel SERVO_OUTPUT_RAW in MAVLink2 |
|
- added MAVLink reporting of logging subsystem health |
|
- added BRD_SAFETY_MASK to allow for channel movement for selected channels with safety on |
|
- lots of HAL_Linux improvements to bus and thread handling |
|
- added IMU heater support on Pixhawk2 |
|
- allow for faster accel bias learning in EKF2 |
|
- added AP_Module support for loadable modules |
|
- merged support for wide range of VRBrain boards |
|
- added support for PH2SLIM and PHMINI boards with BRD_TYPE |
|
- greatly reduced boot time on Pixhawk and similar boards |
|
- fixed magic check for signing key in MAVLink2 |
|
- fixed averaging of gyros for EKF2 gyro bias estimate |
|
- added support for ParametersG2 |
|
- support added for the GPS_INPUT mavlink message |
|
|
|
|
|
|
|
Release 3.0.1, 17 June 2016 |
|
=========================== |
|
The ArduPilot development team is proud to announce the release of |
|
version 3.0.1 of APM:Rover. This is a minor release with small but |
|
important bug fix changes. |
|
|
|
The two main motivations for this release |
|
1. Fixing the arming for skid steering Rovers |
|
2. Fix to the rover steering that should really improve steering of |
|
all rovers. |
|
|
|
Skid Steering Arming |
|
-------------------- |
|
Fixed arming for Skid Steering rovers. You should now be able to arm |
|
your skid steering rover using the steering stick. NOTE skid steering |
|
Rovers - you will not be able to disarm. The reason for this is zero |
|
throttle full left turn is a perfectly valid move for a skid steering |
|
rover as it can turn on the spot. You don't want to be executing this |
|
and have the rover disarm part way through your turn so we have |
|
disabled disarming via the steering stick. You can still disarm from |
|
the GCS. Thanks to Pierre Kancir for working on this. |
|
|
|
Improved Steering Control |
|
------------------------- |
|
For historical reason's the steering controller was using the raw GPS |
|
data for ground speed without any filtering. If you have every graphed |
|
this data you will see on a rover its very spiky and all over the |
|
place. This spiky'ness was feeding into the lateral accel demand and |
|
causing inaccuracies/jitters. Now we using the EKF GPS filtered data |
|
which is much smoother and accurate and the steering control has |
|
greatly improved. |
|
|
|
Improved Cornering |
|
------------------ |
|
Previously when corning we didn't take into account any "lean or tilt" |
|
in the rover - we assumed the turns were always flat. We have changed |
|
this to now take into account any lean so turning should be more |
|
accurate. Boat users should really benefit from this too. |
|
|
|
MAVLink2 support has been added |
|
------------------------------- |
|
See this post by Tridge - |
|
http://discuss.ardupilot.org/t/mavlink2-is-in-ardupilot-master/9188/1 |
|
|
|
|
|
The other changes in this release are: |
|
|
|
- setting your sonar_trigger_cm to 0 will now log the sonar data but |
|
not use it for vehicle avoidance. |
|
- the throttle PID is now being logged |
|
- range finder input is now being captured (thanks to Allan Matthew) |
|
- added LOG_DISARMED parameter |
|
- merge upstream PX4Firmware changes |
|
- numerous waf build improvements |
|
- numerous EKF2 improvements |
|
|
|
|
|
Release 3.0.0, 5 April 2016 |
|
=========================== |
|
The ArduPilot development team is proud to announce the release of |
|
version 3.0.0 of APM:Rover. This is a major release with a lot of |
|
changes so please read the notes carefully! |
|
|
|
A huge thanks to ALL the ArduPilot developers. The Rover code |
|
benefits tremendously from all the hard work that goes into the Copter |
|
and Plane vehicle code. Most of the code changes in this |
|
release were not specifically for Rover however because of the |
|
fantastic architecture of the ArduPilot code Rover automatically get's |
|
those enhancements anyway. |
|
|
|
Note that the documentation hasn't yet caught up with all the changes |
|
in this release. We are still working on that, but meanwhile if you |
|
see a feature that interests you and it isn't documented yet then |
|
please ask. |
|
|
|
The 3.x.x releases and above DON'T support APM1/APM2 |
|
---------------------------------------------------- |
|
This release DOES NOT SUPPORT the old APM1/APM2 AVR based boards. The |
|
issue is the amount of effort required to keep the new code ported to |
|
the old platforms. We are very sorry this has to occur and if there |
|
is someone who is willing and technically capable of doing this work |
|
then please let us know. |
|
There will be a discussion created on ArduPilot forums where people |
|
can request features in the new code be backported to the APM code to |
|
run on the AVR boards and if it is reasonably easy and they are |
|
willing to do the beta testing we will do our best to make it happen. |
|
|
|
EKF2 - New Kalman Filter |
|
------------------------ |
|
Paul Riseborough has been working hard recently on the new |
|
EKF2 variant which fixes many issues seen with the old estimator. The |
|
key improvements are: |
|
|
|
- support for separate filters on each IMU for multi-IMU boards |
|
(such as the Pixhawk), giving a high degree of redundency |
|
- much better handling of gyro drift estimation, especially on |
|
startup |
|
- much faster recovery from attitude estimation errors |
|
|
|
After extensive testing of the new EKF code we decided to make it the |
|
default for this release. You can still use the old EKF if you want to |
|
by setting AHRS_EKF_TYPE to 1, although it is recommended that the new |
|
EKF be used for all vehicles. |
|
|
|
In order to use the EKF we need to be a bit more careful about the |
|
setup of the vehicle. That is why we enabled arming and pre-arm checks |
|
by default. Please don't disable the arming checks, they are there for |
|
very good reasons. |
|
|
|
UAVCAN new protocol |
|
------------------- |
|
The uavcan change to the new protocol has been a long time coming, and |
|
we'd like to thank Holger for both his great work on this and his |
|
patience given how long it has taken to be in a release. This adds |
|
support for automatic canbus node assignment which makes setup much |
|
easier, and also supports the latest versions of the Zubax canbus GPS. |
|
|
|
Support for 4 new Boards |
|
------------------------ |
|
The porting of ArduPilot to more boards continues, with support |
|
for 3 new boards in this release. They are: |
|
|
|
- the BHAT board |
|
- the PXFmini |
|
- the QualComm Flight |
|
- the Pixracer |
|
|
|
More information about the list of supported boards is available here: |
|
http://dev.ardupilot.org/wiki/supported-autopilot-controller-boards/ |
|
|
|
Startup on a moving platform |
|
---------------------------- |
|
One of the benefits of the new EKF2 estimator is that it allows for |
|
rapid estimation of gyro offset without doing a gyro calibration on |
|
startup. This makes it possible to startup and arm on a moving |
|
platform by setting the INS_GYR_CAL parameter to zero (to disable gyro |
|
calibration on boot). This should be a big help for boats. |
|
|
|
Improved Camera Trigger Logging |
|
------------------------------- |
|
This release adds new CAM_FEEDBACK_PIN and CAM_FEEDBACK_POL |
|
parameters. These add support for separate CAM and TRIG log messages, |
|
where TRIG is logged when the camera is triggered and the CAM message |
|
is logged when an external pin indicates the camera has actually |
|
fired. This pin is typically based on the flash hotshoe of a camera |
|
and provides a way to log the exact time of camera triggering more |
|
accurately. Many thanks to Dario Andres and Jaime Machuca for their |
|
work on this feature. |
|
|
|
PID Tuning |
|
---------- |
|
You can now see the individual contributions of the P, I and D |
|
components for the Steering PID in the logs (PIDY), allowing you to |
|
get a much better picture of the performance. |
|
|
|
Vibration Logging |
|
----------------- |
|
This release includes a lot more options for diagnosing vibration |
|
issues. You will notice new VIBRATION messages in MAVLink and VIBE |
|
messages in the dataflash logs. Those give you a good idea of your |
|
(unfiltered) vibration levels. For really detailed analysis you can |
|
setup your LOG_BITMASK to include raw logging, which gives you every |
|
accel and gyro sample on your Pixhawk. You can then do a FFT on the |
|
result and plot the distribution of vibration level with |
|
frequency. That is great for finding the cause of vibration |
|
issues. Note that you need a very fast microSD card for that to work! |
|
|
|
More Sensors |
|
------------ |
|
This release includes support for a bunch more sensors. It now supports |
|
3 different interfaces for the LightWare range of Lidars (serial, I2C |
|
and analog), and also supports the very nice Septentrio RTK |
|
dual-frequency GPS (the first dual-frequency GPS we have support |
|
for). It also supports the new "blue label" Lidar from Pulsed Light |
|
(both on I2C and PWM). |
|
|
|
For the uBlox GPS, we now have a lot more configurability of the |
|
driver, with the ability to set the GNSS mode for different |
|
constellations. Also in the uBlox driver we support logging of the raw |
|
carrier phase and pseudo range data, which allows for post RTK |
|
analysis with raw-capable receivers for really accurate photo |
|
missions. |
|
|
|
Better Linux support |
|
-------------------- |
|
This release includes a lot of improvements to the Linux based |
|
autopilot boards, including the NavIO+, the PXF and ERLE boards and |
|
the BBBMini and the new RasPilot board. |
|
|
|
On-board compass calibrator |
|
--------------------------- |
|
We also have a new on-board compass calibrator, which also adds calibration |
|
for soft iron effects, allowing for much more accurate compass |
|
calibration. |
|
|
|
Lots of other changes! |
|
---------------------- |
|
The above list is just a taste of the changes that have gone into this |
|
release. Thousands of small changes have gone into this release with |
|
dozens of people contributing. Many thanks to everyone who helped! |
|
|
|
Other key changes |
|
----------------- |
|
- fixed the MAV_CMD_DO_SET_HOME (thanks salonijain12) |
|
- fixed bug when reverse throttle would increase speed in AUTO |
|
- fixed a bug going into guided and rover still moving |
|
- loitering at a waypoint if Param1 is non-zero |
|
- update uavcan to new protocol |
|
- fixed reporting of armed state with safety switch |
|
- added optional arming check for minimum voltage |
|
- improved text message queueing to ground stations |
|
- re-organisation of HAL_Linux bus API |
|
- improved NMEA parsing in GPS driver |
|
- improved autoconfig of uBlox GPS driver |
|
- support a wider range of Lightware serial Lidars |
|
- improved non-GPS performance of EKF2 |
|
- improved compass fusion in EKF2 |
|
- improved support for Pixracer board |
|
- improved NavIO2 support |
|
- added BATT_WATT_MAX parameter |
|
- enable messages for MAVLink gimbal support |
|
- use 64 bit timestamps in dataflash logs |
|
- added realtime PID tuning messages and PID logging |
|
- fixed a failure case for the px4 failsafe mixer |
|
- added DSM binding support on Pixhawk |
|
- added vibration level logging |
|
- ignore low voltage failsafe while disarmed |
|
- added delta velocity and delta angle logging |
|
- allow steering disarm based on ARMING_RUDDER parameter |
|
- prevent mode switch changes changing WP tracking |
|
- fixed parameter documentation spelling errors |
|
- send MISSION_ITEM_REACHED messages on waypoint completion |
|
- enable EKF by default on rover |
|
- Improve gyro bias learning rate for plane and rover |
|
- Allow switching primary GPS instance with 1 sat difference |
|
- added NSH over MAVLink support |
|
- added support for mpu9250 on pixhawk and pixhawk2 |
|
- Add support for logging ublox RXM-RAWX messages |
|
- lots of updates to improve support for Linux based boards |
|
- added ORGN message in dataflash |
|
- added support for new "blue label" Lidar |
|
- switched to real hdop in uBlox driver |
|
- improved auto-config of uBlox |
|
- raise accel discrepancy arming threshold to 0.75 |
|
- improved support for tcp and udp connections on Linux |
|
- switched to delta-velocity and delta-angles in DCM |
|
- improved detection of which accel to use in EKF |
|
- improved auto-detections of flow control on pixhawk UARTs |
|
- added HDOP to uavcan GPS driver |
|
- improved sending of autopilot version |
|
- log zero rangefinder distance when unhealthy |
|
- added PRU firmware files for BeagleBoneBlack port |
|
- fix for recent STORM32 gimbal support |
|
- changed sending of STATUSTEXT severity to use correct values |
|
- added new RSSI library with PWM input support |
|
- fixed MAVLink heading report for UAVCAN GPS |
|
- support LightWare I2C rangefinder on Linux |
|
- improved staging of parameters and formats on startup to dataflash |
|
- added new on-board compass calibrator |
|
- improved RCOutput code for NavIO port |
|
- added support for Septentrio GPS receiver |
|
- support DO_MOUNT_CONTROl via command-long interface |
|
- added CAM_RELAY_ON parameter |
|
- moved SKIP_GYRO_CAL functionality to INS_GYR_CAL |
|
- new waf build system |
|
- new async accel calibrator |
|
- better rangefinder power control |
|
- dataflash over mavlink support |
|
- settable main loop rate |
|
- hideable parameters |
|
- improved logging for dual-GPS setups |
|
- improvements to multiple RTK GPS drivers |
|
- numerous HAL_Linux improvements |
|
- improved logging of CAM messages |
|
- added support for IMU heaters in HAL_Linux |
|
- support for RCInput over UDP in HAL_Linux |
|
- improved EKF startup checks for GPS accuracy |
|
- added raw IMU logging for all platforms |
|
- configurable RGB LED brightness |
|
- improvements to the lsm303d driver for Linux |
|
|
|
|
|
Release 2.50, 19 June 2015 |
|
========================== |
|
|
|
The ardupilot development team has released version 2.50 of |
|
APM:Rover. This release is mostly a backend improvement to ArduPilot |
|
but a few new features and bug fixes are included. |
|
|
|
Re-do Accelerometer Calibration |
|
------------------------------- |
|
Due to a change in the maximum accelerometer range on the Pixhawk all |
|
users must re-do their accelerometer calibration for this release. |
|
|
|
|
|
Only 3D accel calibration |
|
------------------------- |
|
The old "1D" accelerometer calibration method has now been removed, so |
|
you must use the 3D accelerometer calibration method. The old method |
|
was removed because a significant number of users had poor experiences. |
|
|
|
|
|
Changes in this release are: |
|
|
|
- CLI_ENABLED parameter added so the CLI can now be accessed |
|
in Rover |
|
- PID logging for the steering controller. It its now |
|
possible to graph what the P, I and D are doing as your |
|
driving the rover around to enable much better tuning of the |
|
vehicle. |
|
- Transition from .pde file to .cpp files for improved |
|
development. |
|
- GIT Submodules created for PX4Firmware, PX4Nuttx and uavcan |
|
git repositories for improved development. |
|
- Followme mode now works for Rover |
|
- GUIDED mode significantly improved. If you have a GCS which is in |
|
Followme mode if the user then changes mode with the RC transmitter to |
|
HOLD or anything else then the Rover will STOP listening to the |
|
Followme updated guided mode waypoints. |
|
- When going into GUIDED mode the rover went into RTL - this |
|
is fixed. |
|
- Added EKF_STATUS_REPORT MAVLink message |
|
- 64-bit timestamps in dataflash logs |
|
- Numerous EKF improvements |
|
- Added support for 4th Mavlink channel |
|
- Added support for raw IMU logging |
|
- updated Piksi RTK GPS driver |
|
- improved support for GPS data injection (for Piksi RTK GPS) |
|
- The SITL software in the loop simulation system has been completely |
|
rewritten for this release. A major change is to make it possible to |
|
run SITL on native windows without needing a Linux virtual |
|
machine. (thanks Tridge) |
|
|
|
|
|
|
|
Release 2.49, March 4th 2015 |
|
---------------------------- |
|
|
|
The ardupilot development team has released version 2.49 of |
|
APM:Rover. This release is a bug fix release with two important bugs |
|
found by Marco Walther - Thanks Marco! |
|
|
|
The bug fixes in this release are: |
|
|
|
- fixed a sonar problem where objects to the left wouldn't be |
|
identified - thanks Marco Walther! |
|
- Fixed the ordering of the AP_Notify call so the main indicator |
|
light would be correct on startup - thanks Marco Walther! |
|
|
|
|
|
|
|
Release 2.48, February 20th 2015 |
|
-------------------------------- |
|
|
|
The ardupilot development team has released version 2.48 of |
|
APM:Rover. This release is a bug fix release with some important bugs |
|
found by the users of ardupilot. |
|
|
|
The changes in this release are: |
|
|
|
- fixed a bug that could cause short term loss of RC control with |
|
some receiver systems and configurations |
|
- allowed for shorter sync pulse widths for PPM-SUM receivers on |
|
APM1 and APM2 |
|
- fix an issue where battery reporting could be intermittent (thanks |
|
Georgii Staroselskii!) |
|
- fixed a mission handling bug that could cause a crash if jump |
|
commands form an infinite loop (thanks to Dellarb for reporting |
|
this bug) |
|
- improved support for in-kernel SPI handling on Linux (thanks to John Williams) |
|
- support UAVCAN based ESCs and GPS modules on Pixhawk (thanks to |
|
Pavel, Holger and and PX4 dev team) |
|
- Multiple updates for the NavIO+ cape on RaspberryPi (thanks to |
|
Emlid) |
|
- Lots of EKF changes |
|
- added support for MAVLink packet routing |
|
- added detection and recovery from faulty gyro and accel sensors |
|
- added support for BBBMini Linux port |
|
- increased number of AVR input channels from 8 to 11 |
|
- auto-set system clock based on GPS in Linux ports |
|
- added SBUS FrSky telemetry support (thanks to Mathias) |
|
- Added AK8963 MAG support (thanks Staroselskii Georgii) |
|
- Added support for second battery |
|
- Auto formatting of SDCard if it cannot be accessed on startup |
|
- A number of significant performance improvements for the PX4 platform |
|
|
|
The most important bug fix is the one for short term loss of RC |
|
control. This is a very long standing bug which didn't have a |
|
noticeable impact for most people, but could cause loss of RC control |
|
for around 1 or 2 seconds for some people in certain circumstances. |
|
|
|
The bug was in the the AP_HAL RCInput API. Each HAL backend has a flag |
|
that says whether there is a new RC input frame available. That flag |
|
was cleared by the read() method (typically hal.rcin->read()). Callers |
|
would check for new input by checking the boolean |
|
hal.rcin->new_input() function. |
|
|
|
The problem was that read() was called from multiple places. Normally |
|
this is fine as reads from other than the main radio input loop happen |
|
before the other reads, but if the timing of the new radio frame |
|
exactly matched the loop frequency then a read from another place |
|
could clear the new_input flag and we would not see the new RC input |
|
frame. If that happened enough times we would go into a short term RC |
|
failsafe and ignore RC inputs, even in manual mode. |
|
|
|
The fix was very simple - it is the new_input() function itself that |
|
should clear the flag, not read(). |
|
|
|
Many thanks to MarkM for helping us track down this bug by providing |
|
us with sufficient detail on how to reproduce it. In Marks case his |
|
OpenLRSng configuration happened to produce exactly the worst case |
|
timing needed to reproduce the issue. Once Tridge copied his OpenLRS |
|
settings to his TX/RX he was able to reproduce the problem and it was |
|
easy to find and fix. |
|
|
|
A number of users have reported occasional glitches in manual control |
|
where servos pause for short periods in past releases. It is likely |
|
that some of those issues were caused by this bug. The dev team would |
|
like to apologise for taking so long to track down this bug! |
|
|
|
The other main change was also related to RC input. Some receivers use |
|
a PPM-SUM sync pulse width shorter than what the APM1/APM2 code was |
|
setup to handle. The OpenLRSng default sync pulse width is 3000 |
|
microseconds, but the APM1/APM2 code was written for a mininum sync |
|
pulse width of 4000 microseconds. For this release we have changed the |
|
APM1/APM2 driver to accept a sync pulse width down to 2700 |
|
microseconds. |
|
|
|
Auto format of SD Card |
|
====================== |
|
From time to time the SD cards in the PX4 autopilots get corrupted. |
|
This isn't a surprise considering what we do to them. Your all |
|
familiar with the windows "please unmount or eject your SDCard before |
|
removing" process. Well we don't do that. In fact normal operation |
|
is to just pull the power on the SDCard - whilst its being written |
|
too!! Not to metion the horrible vibration rich environment the |
|
SDCard exists in. If the autopilot is setup in the internal innards |
|
of your plane/copter/rover this can be a nightmare to get to. To |
|
resolve that problem Tridge has added code at startup so when |
|
ArduPilot tries to mount to SDCard to access it - if that fails it |
|
will then try to format the SDCard and if successful mount the card |
|
and proceed. If the format fails then you will get the usual SOS |
|
Audio that makes most of us want to find the buzzer and rip its heart |
|
out. |
|
|
|
I mention this in case anyone has precious logs saved on the SDCard or |
|
they are using the SDCard out of their phone with their wedding |
|
photo's on it. Probably best not to do that and assume any data on |
|
the SDCard can be deleted. |
|
|
|
We are also looking to add a parameter to control whether the card is |
|
auto formatted on startup or not but it isn't in there yet. |
|
|
|
|
|
|
|
Release 2.47, November 15th 2014 |
|
-------------------------------- |
|
|
|
The ardupilot development team is proud to announce the release of |
|
version 2.47 of APM:Rover. This is a minor bug fix release. The most |
|
important change in this release is the fixing of the skid steering |
|
support but there have been a number of fixes in other areas as well. |
|
|
|
Full changes list for this release: |
|
|
|
- add support for controlling safety switch on Pixhawk from ground station |
|
|
|
- prevent reports of failed AHRS during initialisation |
|
|
|
- fixed skid steering that was broken in the last release |
|
|
|
- report gyro unhealthy if gyro calibration failed |
|
|
|
- fixed dual sonar support in CLI sonar test |
|
|
|
- fixed Nuttx crash on Pixhawk with bad I2C cables |
|
|
|
- added GPS_SBAS_MODE parameter - turns on/off satellite based augemtation system for GPS |
|
|
|
- added GPS_MIN_ELEV parameter - specifiy the elevation mask for GPS satellites |
|
|
|
- added RELAY_DEFAULT parameter to control default of relay on startup |
|
|
|
- fixed bug in FRAM storage on Pixhawk that could cause parameters changes not to be saved |
|
|
|
- better handling of compass errors in the EKF (Extended Kalman Filter) |
|
|
|
- improved support for linux based autopilots |
|
|
|
- added support for PulsedLight LIDAR as a range finder |
|
|
|
Many thanks to everyone who contributed to this release, especially |
|
Tom Coyle and Linus Penzlien for their excellent testing and feedback. |
|
|
|
Happy driving! |
|
|
|
|
|
|
|
Release 2.46, August 26th 2014 |
|
------------------------------ |
|
|
|
The ardupilot development team is proud to announce the release of |
|
version 2.46 of APM:Rover. This is a major release with a lot of new |
|
features and bug fixes. |
|
|
|
This release is based on a lot of development and testing that |
|
happened prior to the AVC competition where APM based vehicles |
|
performed very well. |
|
|
|
Full changes list for this release: |
|
|
|
- added support for higher baudrates on telemetry ports, to make it |
|
easier to use high rate telemetry to companion boards. Rates of up |
|
to 1.5MBit are now supported to companion boards. |
|
|
|
- new Rangefinder code with support for a wider range of rangefinder |
|
types including a range of Lidars (thanks to Allyson Kreft) |
|
|
|
- added logging of power status on Pixhawk |
|
|
|
- added PIVOT_TURN_ANGLE parameter for pivot based turns on skid |
|
steering rovers |
|
|
|
- lots of improvements to the EKF support for Rover, thanks to Paul |
|
Riseborough and testing from Tom Coyle. Using the EKF can greatly |
|
improve navigation accuracy for fast rovers. Enable with |
|
AHRS_EKF_USE=1. |
|
|
|
- improved support for dual GPS on Pixhawk. Using a 2nd GPS can |
|
greatly improve performance when in an area with an obstructed |
|
view of the sky |
|
|
|
- support for up to 14 RC channels on Pihxawk |
|
|
|
- added BRAKING_PERCENT and BRAKING_SPEEDERR parameters for better |
|
breaking support when cornering |
|
|
|
- added support for FrSky telemetry via SERIAL2_PROTOCOL parameter |
|
(thanks to Matthias Badaire) |
|
|
|
- added support for Linux based autopilots, initially with the PXF |
|
BeagleBoneBlack cape and the Erle robotics board. Support for more |
|
boards is expected in future releases. Thanks to Victor, Sid and |
|
Anuj for their great work on the Linux port. |
|
|
|
- added StorageManager library, which expands available FRAM storage |
|
on Pixhawk to 16 kByte. This allows for 724 waypoints, 50 rally |
|
points and 84 fence points on Pixhawk. |
|
|
|
- improved reporting of magnetometer and barometer errors to the GCS |
|
|
|
- fixed a bug in automatic flow control detection for serial ports |
|
in Pixhawk |
|
|
|
- fixed use of FMU servo pins as digital inputs on Pixhawk |
|
|
|
- imported latest updates for VRBrain boards (thanks to Emile |
|
Castelnuovo and Luca Micheletti) |
|
|
|
- updates to the Piksi GPS support (thanks to Niels Joubert) |
|
|
|
- improved gyro estimate in DCM (thanks to Jon Challinger) |
|
|
|
- improved position projection in DCM in wind (thanks to Przemek |
|
Lekston) |
|
|
|
- several updates to AP_NavEKF for more robust handling of errors |
|
(thanks to Paul Riseborough) |
|
|
|
- lots of small code cleanups thanks to Daniel Frenzel |
|
|
|
- initial support for NavIO board from Mikhail Avkhimenia |
|
|
|
- fixed logging of RCOU for up to 12 channels (thanks to Emile |
|
Castelnuovo) |
|
|
|
- code cleanups from Silvia Nunezrivero |
|
|
|
- improved parameter download speed on radio links with no flow |
|
control |
|
|
|
Many thanks to everyone who contributed to this release, especially |
|
Tom Coyle and Linus Penzlien for their excellent testing and feedback. |
|
|
|
Happy driving!
|
|
|