Fixes a potential error where changes to timing and arrival rate of magnetometer and baro data could block the fusion of synthetic position and velocity measurements, allowing unrestrained tilt errors during operation without GPS or optical flow.
Fusion of synthetic position or velocity measurements is now timed to coincide with fusion of barometer observations.
If a new barometer observation has not arrived after 200 msec then the synthetic position or velocity is fused anyway so that fusion of synthetic position or velocity observations cannot occur any slower than 5 Hz
Previous check default only checked the number of satellites and horizontal position accuracy.
Updated default value also checks HDoP and speed accuracy.
Fixes the issue of three unused variables, two of which were used in a
commented Debug() call.
To keep the convenient debug message (and the variable names for the
data bytes), this patch uncomment the debug call but wrap the variables
and the debug call around an ifdef for the local symbol
gsof_DEBUGGING. So by turning it on, the debug will already be in place.
The Debug() call was modified to actually compile and include the third
variable in the output.
It uses a heating resistor controlled by a pwm.
By changing the duty cycle of the pwm, we can control the temperature.
A simple PI algorithm is used in order to get to the correct temperature
fast enough and without too much overshoot
It is implemented as a member of the Util class in order not to make to much
modification to the current codebase
Read temperature as part of the normal burst. This is not very costly since it
is part of the burst read in i2c and already read in spi.
It is meant to be used for imu heating.
The filter is set to 1Hz on temperature because of the inherent inertia of
heating systems.
Surround calls to rcout->write() with rcout->cork() and rcout->push().
If the RCOutput implementation allows the writes are grouped and only
sent together to the underlying hardware.
Fix warning and use htole16 instead of trying to implement it.
The current code does nothing on little endian platforms.
Moreover, the status variable was unused.
MPU6000 data sheet indicates that variation on gyro ZRO across temperature range from -40 to +85 is +-20 deg/sec.
The limits on the gyro bias states have been increased to allow for this.
To enable the EKF to accommodate such large gyro bias values in yaw without the yaw error wrapping, leading to continual heading drift, an unwrap function has been applied to the compass heading error.
In 294298e ("AP_InertialSensor: use method for downcast") I was too eager
to use "auto" and ended up using the implicit copy constructor instead
of actually getting a reference to the object.
This was only used for supporting APM1. The removal was mostly automatic
with:
sed -i 's/pgm_read_byte(&_motor_to_channel_map\[\([^]]*\)\])/\1/g' libraries/AP_Motors/*.cpp
sed -i 's/_motor_to_channel_map\[\([^]]*\)\]/\1/g' libraries/AP_Motors/*.cpp
And then remove references to MOTOR_TO_CHANNEL_MAP and
_motor_to_channel_map and make sure the variable used in shifts is
unsigned
This method is not used anymore since the introduction of channel map and
allowing motors to be enabled/disabled in AP_Motors.
Later we may introduce a method to write multiple values with a default
implementation that supports the channel and enable maps rather than
requiring all subclasses to implement this method.
This is the only place where this variant of RCOutput::write() is
called. Remove it so to use the common interface. It can be added back
later when there's support for asynchronous write.
Now that most places in the code use the ARRAY_SIZE macro instead of
coding it by hand, let's use some type safety in its definition. This is
a C++ version of similar macros used in kmod, Linux kernel and the
source of them, ccan.
A C++ version like this is used in V8 (the JS engine) and other open
source projects.
The main benefit of this version is that you get a compile error if you
pass in a variable that's not an array. For example,
Bla y[10];
Bla *y_ptr = y;
void foo(Bla x[])
{
// build error since x[] decay to a pointer in function
// parameter
for (int i = 0; i < ARRAY_SIZE(x); i++) {
...
}
// build error since y_ptr is not an array
for (int i = 0; i < ARRAY_SIZE(y_ptr); i++) {
...
}
}
I added the additional specialization to allow arrays of size 0.
If there is a read error, reading from the adc will return 0 but moreover,
we need to re-initiate a read or else we are stuck forever.
From MS5611-01BA03 datasheet, p. 10, CONVERSION SEQUENCE:
"After the conversion, using ADC read command the result is clocked out with the MSB first.
If the conversion is not executed before the ADC read command, or the ADC read command is
repeated, it will give 0 as the output result."
Instead of just doing a static cast to the desired class, use a method
named "from". Pros:
- When we have data shared on the parent class, the code is cleaner in
child class when it needs to access this data. Almost all the data
we use in AP_HAL benefits from this
- There's a minimal type checking because now we are using a method
that can only receive the type of the parent class
Instead of just doing a static cast to the desired class, use a method
named "from". Pros:
- When we have data shared on the parent class, the code is cleaner in
child class when it needs to access this data. Almost all the data
we use in AP_HAL benefits from this
- There's a minimal type checking because now we are using a method
that can only receive the type of the parent class
Instead of just doing a static cast to the desired class, use a method
named "from". Pros:
- When we have data shared on the parent class, the code is cleaner in
child class when it needs to access this data. Almost all the data
we use in AP_HAL benefits from this
- There's a minimal type checking because now we are using a method
that can only receive the type of the parent class
Instead of just doing a static cast to the desired class, use a method
named "from". Pros:
- When we have data shared on the parent class, the code is cleaner in
child class when it needs to access this data. Almost all the data
we use in AP_HAL benefits from this
- There's a minimal type checking because now we are using a method
that can only receive the type of the parent class