Now variables don't have to be declared with PROGMEM anymore, so remove
them. This was automated with:
git grep -l -z PROGMEM | xargs -0 sed -i 's/ PROGMEM / /g'
git grep -l -z PROGMEM | xargs -0 sed -i 's/PROGMEM//g'
The 2 commands were done so we don't leave behind spurious spaces.
AVR-specific places were not changed.
The PSTR is already define as a NOP for all supported platforms. It's
only needed for AVR so here we remove all the uses throughout the
codebase.
This was automated with a simple python script so it also converts
places which spans to multiple lines, removing the matching parentheses.
AVR-specific places were not changed.
This allows turning on/off desired velocity feedforward without setting desired_vel.z to zero. Setting desired_vel.z to zero has the side effect of disrupting the landing detection which needs to know if we are trying to descend
This increase in assumed altimeter noise and reduction in accel noise has been flight tested by L.Hall with noticeable reduction in the immediate response to Baro errors during moving flight.
This increases the time constant of response to baro errors such that the pilot can more easily compensate.
The previous gain from rate to magnetometer error was excessive. The revised value is equivalent to a magnetic field length of 0.5 with a timing uncertainty of 0.01 sec
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.
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.
We are using a microcontroller to read the PWM input from RC. The read
values are sent to our board using a simple serial protocol through the
UART interface.
This patch interprets these values and passes them forward to the APM.
If the baro data and magnetometer data are interleaved (arriving every 100 msec and offset by 50 msec), then the filter will go unstable during startup and fail to complete checks.
Since we are using uint8_t and uint16_t types we need to include the
correspondent system header. Otherwise it would depend on the include
order of who is including this particular header, causing failures as we
move headers around.
This sets the fusion of the synthetic position and velocity to occur at the same time as the barometer
This makes filter tuning more consistent between GPS and non-GPS useage
High measurement data rates can fill buffers with data that is always new and never fused because it is over-written before it falls behind the measurement time horizon.
new param: NAVL1_XTRACK_I
// @Description: Crosstrack error integrator gain. This gain is applied to the crosstrack error to ensure it converges to zero. Set to zero to disable. Smaller values converge slower, higher values will cause crosstrack error oscillation.
fixes https://github.com/diydrones/ardupilot/issues/2650
when param is changed the integrator is set to zero. This makes for easier tuning by seeing it converge to zero on each change.
This option now is passed when instantiating the code in ArduCopter, so
selecting the default value at compile time is not necessary anymore.
The motivation is to move vehicle specifc code out of the general
libraries. This patch shouldn't change behavior.
The AHRS_EKF_USE_ALWAYS define is used to force EKF to be always
used. It is defined only for building ArduCopter. Change it to be a
runtime flag. Keep its default value still based on the original define,
once the Copter uses it the define will be removed.
The motivation is to move vehicle specifc code out of the general
libraries. This patch shouldn't change behavior.
For all supported boards the maximum number of instances is 3. The
number of HIL_COMPASSES was already defined as 2 instead of 3, so this
is left as before.
We don't support HAL_CPU_CLASS <= HAL_CPU_CLASS_16 anymore. This makes
COMPASS_MAX_INSTANCES and COMPASS_MAX_BACKEND constant for all supported
boards.
We don't support HAL_CPU_CLASS <= HAL_CPU_CLASS_16 anymore. This makes
INS_MAX_INSTANCES, INS_MAX_BACKENDS and INS_VIBRATION_CHECK constant for
all supported boards.
The code with ifdef for !FAST_SAMPLING is bit rotting and the example
for AP_InertialSensor is currently broken for this case. Instead of
adding more ifdefs, remove the legacy implementation for !FAST_SAMPLING
since we don't support it anymore.
Reported by Grant:
/home/grant/3dr/ardupilot/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp:
In member function 'void AP_InertialSensor_MPU6000::_accumulate(uint8_t*,
uint8_t)':
/home/grant/3dr/ardupilot/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp:776:20:
error: no match for 'operator+=' (operand types are 'Vector3l {aka
Vector3<long int>}' and 'Vector3f {aka Vector3<float>}')
_accel_sum += accel;
/home/grant/3dr/ardupilot/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp:777:19:
error: no match for 'operator+=' (operand types are 'Vector3l {aka
Vector3<long int>}' and 'Vector3f {aka Vector3<float>}')
_gyro_sum += gyro;
Add libraries that those boards depend on. This should be handled in the
future elsewhere (and once for each board), but for now let's make it
compile again.
Remove unnecessary includes, in particular the includes for specific
boards. The list of libraries for 'polygon' example was updated so that
the example compiles again.
This is going to be used by vehicles that already have an object with
setup/loop functions. The vehicle object will just implement the
HAL::Callbacks interface.
Move the macros to a single place and reduce the variations not based on
board, but based on
- The name of the entry-point function, specified by AP_MAIN;
- Whether it contains argc/argv arguments or not.
The goal here is that programs (vehicles and examples) don't need to
include all possible boards to define a main function. Further patches
will change the programs.
Add run method, that encapsulate any mainloop logic on behalf of the
client code. The setup/loop functions are passed via a HAL::Callbacks
interface. The AP_HAL_MAIN() macro should be kept as trivial as
possible.
This interface should be implemented by the existing vehicle objects. To
make easy for the examples (that don't have the equivalent of vehicle
objects), a FunCallbacks was added to bridge to the functions directly.
Instead of requiring every program to specify the HAL related modules,
let the build system do it (in practice everything we compiled depended
on HAL anyway). This allow including only the necessary files in the
compilation.
The switching between different AP_HAL was happening by giving different
definitions of AP_HAL_BOARD_DRIVER, and the programs would use it to
instantiate.
A program or library code would have to explicitly include (and depend)
on the concrete implementation of the HAL, even when using it only via
interface.
The proposed change move this dependency to be link time. There is a
AP_HAL::get_HAL() function that is used by the client code. Each
implementation of HAL provides its own definition of this function,
returning the appropriate concrete instance.
Since this replaces the job of AP_HAL_BOARD_DRIVER, the definition was
removed.
The static variables for PX4 and VRBRAIN were named differently to avoid
shadowing the extern symbol 'hal'.
The legacy EKF switches GPs aiding on on arming, whereas the new EKF switches it on based on GPS data quality.
This means the decision to arm and therefore the predicted solution flags must now reflect the actual status of the navigation solution as it will no longer change when motor arming occurs.
If high vibration levels cause offsets between the two, it switches to the accelerometer with lower vibration levels. The default behaviour is to use the average of both accelerometers.
Don't fuse other measurements on the same frame that magnetometer measurements arrive if running at a high frame rate as there will be insufficient time to complete other operations.