Follow the following order for includes:
- Corresponding header file (if exists)
- System headers
- Other ArduPilot library headers
- "Local" headers (from the same library)
Testing on different platforms has shown that the new EKF has smaller innovations enabling innovation consistency checks that reject GPS and baro errors to be tightened.
The position and velocity thresholds for plane have been left the same because planes are less sensitive to GPS glitches as they fly higher and with more separation to surrounding objects. They are also more prone to bad inertial data due to the installation practices.
The altitude noise has been increased on plane to allow for the larger baro disturbances that result from the higher speeds and lack of a proper static pressure source. The innovation consistency gate has been adjusted to provide the same baro error limit of ~20m before baro is rejected.
Extended GPS loss can result in the earth field states becoming rotated and making it difficult for the EKF to recover its heading when GPS is regained.
During prolonged GPS outages, the position covariance can become large enough to cause the reset function to continually activate. This is fixed by ensuring that position covariances are always reset when the position is reset.
The innovation variance was being used incorrectly instead of the state variance to trigger the glitch reset.
Because we have changed the yaw angle and have taken a point sample on the magnetic field, covariances associated with the magnetic field states will be invalid and subsequent innovations could cause an unwanted disturbance in roll and pitch.
The reset of the Euler angles to a new yaw orientation was being done using roll and pitch from the output observer states, not the EKF state vector which meant that when roll and pitch were changing, the reset to a new yaw angle would also cause a roll and pitch disturbance.
This was introduced with the HAL rework:
In file included from /p/ardupilot/libraries/AP_HAL/AP_HAL.h:11:0,
from /p/ardupilot/ArduCopter/Copter.h:35,
from /p/ardupilot/ArduCopter/ArduCopter.cpp:76:
/p/ardupilot/ArduCopter/ArduCopter.cpp: In function 'int ArduPilot_main(int, char* const*)':
/p/ardupilot/libraries/AP_HAL/AP_HAL_Main.h:11:26: warning: no previous declaration for 'int ArduPilot_main(int, char* const*)' [-Wmissing-declarations]
#define AP_MAIN __EXPORT ArduPilot_main
^
It's due to PX4 using that warning as opposed to Linux. Since it harmless, add
the prototype for everybody.
ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp: In member
function 'int32_t Linux::Storage_FRAM::read(uint16_t, uint8_t*, uint16_t)':
/home/lucas/p/dronecode/ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp:183:24: war
ning: comparison is always false due to limited range of data type [-Wtype-limits]
if(Buff[i-fptr]==-1){
^
For the general case, pragma once is better replacement for of include
guards. One line instead of three, less scopes to close in the end of
the file, no chance to having the outdated names in the define symbol.
Remove unnecessary includes, reorder them in blocks separated by a blank
line
- Corresponding header file (if exists)
- System headers
- Other ArduPilot library headers
- "Local" headers (from the same library)
Now that SITL is compiled only when it's needed (i.e. using the SITL
board), there's no need to ifdef its files based on the
CONFIG_HAL_BOARD. So remove them.
Include board-specific files only when the board is used. Since these
should be exceptional cases, let the includer handle the ifdef instead
of putting ifdefs in every platform-specific header.
In the future we should evaluate whether the HAL for the board should
instantiate this.
Include board-specific files only when the board is used. Since these
should be exceptional cases, let the includer handle the ifdef instead
of putting ifdefs in every platform-specific header.
In the future we should evaluate whether the HAL for the board should
instantiate this.
Include board-specific files only when the board is used. Since these
should be exceptional cases, let the includer handle the ifdef instead
of putting ifdefs in every platform-specific header.
In the future we should evaluate whether the HAL for the board should
instantiate this.
Include board-specific files only when the board is used. Since these
should be exceptional cases, let the includer handle the ifdef instead
of putting ifdefs in every platform-specific header.
In the future we should evaluate whether the HAL for the board should
instantiate this.
Include board-specific files only when the board is used. Since these
should be exceptional cases, let the includer handle the ifdef instead
of putting ifdefs in every platform-specific header.
In the future we should evaluate whether the HAL for the board should
instantiate this.
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
Delta angle calculation is now unified, so there is no need for such a method.
That also avoids developers thinking they need that method being called
somewhere in their new drivers.
This commit basically moves delta angle calculation that was previously done in
AP_InertialSensor_PX4 to a common place. Instances must publish their gyro raw
sample rate to enable delta angle calculation.
The delta velocity calculation is now unified, so there is no need for such a
method. That also avoids delevopers thinking they need that method being called
somewhere in their new drivers.
This commit basically moves delta velocity calculation that was previously done
in AP_InertialSensor_PX4 to a common place. Instances must publish their accel
raw sample rate to enable delta velocity calculation.
Now that we are using a consistent 50Hz minimum update rate for the covariance prediction we do not need a different initial gyro bias uncertainty for plane and copter to maintain filter stability margins.
The default value of 0.1 rad/s was too high and gave excessive settling time of the filter attitude after startup.
The initial attitude uncertainty has been increased to allow for some movement during startup.
This commit adds the class Linux::GPIO_Sysfs. This class provides a generic
implementation of AP_HAL::GPIO on Linux by using GPIO Sysfs Interface
(https://www.kernel.org/doc/Documentation/gpio/sysfs.txt).
The channel() interface should be preferred in places that need to be
fast. Since it maintains the file descriptor open this is much faster
than opening and closing it.