When building for px4-v2 we have an warning because we are checking for
the value of this undefined macro. Just change both checks to use
"defined()".
../../libraries/AP_HAL_PX4/Util.cpp:115:7: warning: "CONFIG_ARCH_BOARD_PX4FMU_V4" is not defined [-Wundef]
#elif CONFIG_ARCH_BOARD_PX4FMU_V4
^
when this is set the board RGB LED will be controlled by MAVLink
instead of internally. This is useful for cases where the LED patterns
and colours needed are specified by an external authority (such as the
OBC organisers)
When switching over to a back up magnetometer, ensure that the earth field estimate are reset. other wise mag earth field estimates due to the previous failed mag could cause data from the new mag to be rejected.
This bug created a race condition whereby if the EKF had to reset the yaw to the GPS ground course to recover from a bad magnetometer, the new heading could be over-written by the bad magnetic heading when the plane reached the height for the scheduled reset.
If the GPS receiver was disconnected and no data received, then then the gpsGoodToAlign check did not get a chance to run and becasue it was previously true the EKF would switch back into aiding.
This prevents this by ensuring that gpsGoodToAlign defaults to false when the check is not being performed.
An additional check has also been dded to ensure that there is GPS data to fuse before we declare ready to use GPS.
Switching in and out of aiding modes was being performed in more than one place and was using two variables.
The reversion out of GPS mode due to prolonged loss of GPS was not working.
This consolidates the logic and ensures that PV_AidingMode is only changed by the setAidingMode function.
The filter status logic calculations were being repeated every time the get function was called.
The logic is now updated once per filter update step and a separate get function added
Split publishing of local position into horiz and vert components with separate validity checks
Split status reporting into separate update and get functions and only update once after each loop update. This removes unnecessary re-calculation of the status logic and ensures all consumers get the same data (avoid possible race conditions).
If we start GPS aiding before the gyro bias variances have reduced, glitches on the GPS can cause attitude disturbances that degrade flight accuracy during early flight.
The minimum version for gcc was supposed to be 4.9 for any platform.
However our build instructions are outdated. Remove the problematic
parts that use the sparse-endian.h header while we don't fix the setup
for windows.
When building for px4-v2 we have an warning because we are checking for
the value of this undefined macro. Just change both checks to use
"defined()".
../../libraries/AP_BoardConfig/AP_BoardConfig.cpp:36:7: warning: "CONFIG_ARCH_BOARD_PX4FMU_V4" is not defined [-Wundef]
#elif CONFIG_ARCH_BOARD_PX4FMU_V4
^
during the first part of a takeoff when we have not yet reached the
target airspeed this forces the throttle to maximum. This fixes a case
where the throttle may drop too low during the first part of takeoff
and lead to a stall.
The reason of defining BMI160_MAX_FIFO_SAMPLES as 8 can be found on the
following histogram of the number of samples in the FIFO on each read while
performing the accelerometer calibration process:
Samples Count Freq Acc. Freq
------------------------------
1 3842 0.1201 0.120111
2 13172 0.4118 0.531904
3 9065 0.2834 0.815300
4 2710 0.0847 0.900022
5 2231 0.0697 0.969769
6 816 0.0255 0.995279
7 137 0.0043 0.999562
8 13 0.0004 0.999969
13 1 0.0000 1.000000
Using factory method maked it easier to grasp the lifetime of all object
that get created and destroyed. Instead of spanning this thoughout whole
source file we have it nicely encapsulated in this a little horrendeous
_parseDevicePath that is of course to improve more.
Otherwise we're going to leak memory without any need.
Before this fix we've created ConsoleDevice 4 times in case -A switch hadn't been supplied,
but we hadn't ever deleted those. Now there's no memory leak here.
Minor changes to follow coding style and improve readability:
- sort headers
- move struct definition to compilation unit rather than header
- Add braces to if, for, etc
- Initialize device on hw_init() method, allowing it not to be
present
- Add missing lock
- Add packed attribute to structs
- Move defines to source file
- Add missing semaphore take on bus
- Initialize device on init function rather than constructor: the
constructor may run before I2CDeviceManager is initialized since our
AP_Notify objects are static so it can't be used.
In _start_conversion(), the check for return code of _dev->transfer() was
inverted. The structure also needs to be PACKED, otherwise there will be
a hole in the middle. Fix these issues and use be16_t where it makes
sense.
In read() we need to check for the second byte of config register, so
either make it an array of uint8_t or convert from big endian to host
endianness. It's simpler to leave it as it was, accessing just the
first byte. Also the conversion value is in be16 type an needs to be
converted to host endiannes, not the opposite.
Fix bus number: all boards that use it expect it to be on bus 1, not 0.
this allows for external modules to be called at defined hook
locations in ArduPilot. The initial example is a module that consumes
the AHRS state, but this can be generalised to a wide variety of hooks
Co-variances were being re-zeroed after being set. This meant that the initial declination learning was sensitive to measurement errors which could result in poor initial yaw accuracy.
Fixes bugs that prevented planes being able to reset yaw to GPS to recovery from takeoff with a bad magnetoemter.
1) If the velocity innovation check had not failed by the time the in-air transition occurred, then the yaw reset would not be performed
2) The velocity states were not being reset
3) The non fly-forward vehicle (copter) reset could occur first and effectively lock out the fly-forward vehicle (plane) yaw check.
Remember the mag bias and earth field states learned during flight when the vehicle lands.
This improves performance for vehicles that do multiple flight on one power cycle
Provide consistent overshoot of 5% across a wider range of time constants and prevent selection of larger time constants causing 'ringing' in the position and velocity outputs.
Fixes a problem observed in a flight log where rapid temperature change caused the accel bias to change faster than the EKF could keep up.
This allows the bias to be learned faster but with acceptable level of noise in the estimate
IMU data was being corrected before being used by the co-variance prediction, whereas the delta angles and velocities in the derivation were supposed to be uncorrected.
This patch creates separate variable for the corrected data
Volatile will provide protection to sequence re-ordering and guarantee
the variable is fetched from memory, but it won't provide the memory
barrier needed to ensure that no re-ordering (by either the compiler or
the CPU) will happen among other threads of execution
accessing the same variables.
For more info about this effect can be found on articles about
std::memory_order.
When using reserved(), the reserved memory cannot be read before it's
written, therefore we cannot update 'tail' until the caller of
reserved() is done writing.
To solve that, a method called 'commit()' was added so the caller can
inform that is done with the memory usage and is safe to update 'tail'.
The caller also has to inform the length that was actually written.
This solution was developed to work considering the usage context of
this class: 1 reader and 1 writer **only**.
Adds a method called `reserve()`, that will take a ByteBuffer::IoVec
array of at least two elements, and return the number of elements
filled out. 0 will be returned if `len` is over the total space of
the buffer; 1 will be returned if there's enough contiguous bytes in
the buffer; 2 will be returned if there are two non-contiguous blocks
of memory.
This method is suitable to be used with POSIX system calls such as
readv(), and is an optimization to not require temporary memory copies
while reading from a file descriptor.
Also modify the write() method to use reserve(), so that similar checks
are performed only in one place.
Modify ByteBuffer class to have a `peekiovec()` method, that takes in a
`struct IoVec` array (similar to `struct iovec` from POSIX), and a
number of bytes, and returns the number of elements from this array
that have been filled out. It is either 0 (buffer is empty), 1
(there's enough contiguous bytes to read that amount) or 2 (ring buffer
is wrapping around).
This enables using scatter-gather I/O (i.e. writev()), removing calls
to memcpy(). That's one call when no wrap-around is happening, and
two calls if it is.
Also, rewrite `ByteBuffer::peekbytes()` to use `peekiovec()`, so that
some of the checks performed by the former are not replicated in the
latter.
- Correctly sort includes and add missing AP_Math.h
- Use anonymous struct for trim_registers in _load_trim_values,
renaming its members so they don't start with underscore
- Don't change _dig* values when we failed to read from sensor
- Add some blank lines
- Make _dig_* members be inside a _dig struct
- Use constrain_int32 instead of if/else chain
- s/time_us/time_usec/
- Construct raw_field with a single constructor in _update()
- Add missing copyright notice
- Group methods together in declaration
this gives more control over throttle for petrol
helis. H_RSC_POWER_NEGC allows for a asymmetric V-curve, which allows
for less power being put into the head when landing or when sitting on
the ground. That can lead to significantly less vibration and chance
of ground oscillation. A heli not being flown with aerobatics does not
need to use high throttle at negative collective pitch.
The H_RSC_SLEWRATE allows for a maximum throttle slew rate to be
set. Some petrol motors can cut if the throttle is moved too
quickly. We had this happen at a height of 6m when switching from
ALT_HOLD to STABILIZE mode. It also lowers the chance of the blades
skewing in their holders with the sudden change of power when the heli
is disarmed. In general it is a bad idea to do instantaneous large
movements of a IC engine throttle.
Magnetometer bias states will subject to larger errors early in flight before flight motion makes the offsets observable and the state variances reduce.
Adds a check on state variances.
Replaces the parameter check with a check of the actual filter fusion method being used.
Allow different process noise to be set for body (sensor bias) and earth field states.
This allows a stable magnetometer bias estimate to be available at end of flight whilst still allowing for external magnetic anomalies during landing.
Adjust default values to give stable mag bias learning and fast learning of external anomalies.
Automatically use the highest gain consistent with a 5% overshoot to minimise RMS tracking errors.
Provide an alternative correction method for the position and velocity states that allows the user to specify the time-constant. This can be used to fine tune the output observer for for platform specific sensor errors and control loop sensitivity estimation noise.
The toilet bowling check during early flight has been removed. This check caused problems where bad compass calibration was the cause of the toilet bowling and resetting to the compass was a bad option. The handling of simultaneous failed mag and velocity innovations is already handled outside the EKF by the failsafe.
A check for yaw errors due to a ground based magnetic anomaly has been introduced.
The logic for in-flight yaw and magnetic field resets has been cleaned up and variable names improved.
Many of our SPI and I2C sensors define the protocol of setting the most
significant bit of the register address in order to perform a read operation.
Thus, enable the use of a "read flag" that is ORed with the register's address.
Since this is an abstraction for general devices, it's a good idea to have zero
as the default value for that flag.
While at it, add documentation to read_registers().