if we load an element other than the X element of a Vector3f via
MAVLink then the value reported back to the GCS would be at the wrong
offset in memory. This led to some very confusing results for users
- throttle slew rate was using % full range including the negative range (-100 to +100 instead of 0 to 100) which meant it was faster
- throttle integrator windup limit was higher than normal because it's a porportional to throttle max - min but that makes no sense when min is negative causing larger limits
On early versions of minlure an RGB LED was wrongly placed next to the
barometer, causing trouble on it.
Additionally depending on the LED intensity it may be a pain to leave it
turned on for boards supposed to be used for bench testing. This allows
to disable the LED by software so we don't have to remove it.
// @Description: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in speed and height. If set to 0 then TECS_PTCH_DAMP will be used instead.
+ // @Description: This is the damping gain for the throttle demand loop during and auto-landing. Same as TECS_THR_DAMP but only in effect during an auto-land. Increase to add damping to correct for oscillations in speed and height. When set to 0 landing throttle damp is controlled by TECS_THR_DAMP.
Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX and TKOFF_THR_MAX) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX) if demanding the current max and under the watt max.
ERB - Emlid Reach Binary protocol.
That driver designed for communication between Reach
and ArduPilot.
Provided opportunities:
- Detection of the driver
- Parsing of input messages: status of transmitter
and navigation information.
- Inject GPS messages from base
Use an Euler yaw heading that switches between a 321 and 312 rotation
sequence to avoid areas of singularity. Using Euler yaw decouples the
observation from the roll and pitch states and prevents magnetic
disturbances from affecting roll and pitch via the magnetometer fusion
process.
- got rid of a lot of not needed defines
- allocated channels on init instead of accessing them every time
through the HAL reference
- simpliefied hw_set_rgb()
Pixracer has FRAM on the same bus as the ms5611 and the FRAM ramtron
driver does not use the same locking mechanism as other px4 SPI
drivers. We need to disable interrupts during FRAM transfers to ensure
we don't get FRAM corruption
The use of yaw angle fusion during startup and ground operation causes problems with tail-sitter vehicle types.
Instead of observing an Euler yaw angle, we now observe the yaw angle obtained by projecting the measured magnetic field onto the the horizontal plain.
This avoids the singularities associated with the observation of Euler yaw angle.
../../libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp:63:5: warning: "WITH_GPS" is not defined [-Wundef]
#if WITH_GPS
^
g_gps was not even declared so remove it.
<command-line>:0:18: warning: "HAL_BOARD_LINUX" is not defined [-Wundef]
../../libraries/AP_Notify/Buzzer.h:20:5: note: in expansion of macro ‘CONFIG_HAL_BOARD’
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
^
In file included from ../../libraries/AP_Notify/Buzzer.cpp:18:0:
../../libraries/AP_Notify/Buzzer.h:20:25: warning: "HAL_BOARD_VRBRAIN" is not defined [-Wundef]
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
^
pid.imax() has type int16_t
../../libraries/PID/examples/pid/pid.cpp:36:53: warning: format ‘%f’ expects argument of type ‘double’, but argument 6 has type ‘int’ [-Wformat=]
pid.kP(), pid.kI(), pid.kD(), pid.imax());
^
../../libraries/Filter/examples/Derivative/Derivative.cpp:16:14: warning: ‘float noise()’ defined but not used [-Wunused-function]
static float noise(void)
^
../../libraries/AP_HAL/examples/UART_test/UART_test.cpp:13:28: warning: ‘uarts’ defined but not used [-Wunused-variable]
static AP_HAL::UARTDriver* uarts[] = {
^
The innovation calculation should have been updated when the heading fusion maths was updated.
We now use a direct heading or yaw angle measurement in the derivation, not the difference between observed and published declination.
This removes a legacy design concept that is no longer required in this filter implementation. Planes will not be armed without EKF aiding and the proposed copter throw mode also requires EKF aiding to be operating.
The other problem with interrupting fusion during the launch is it doesn't reduce the corrections, it just delays them as wen the launch completes, the EKF inertial position estimate is still moving still moved and the corrections are therefore just delayed by the short launch interval.
Thank you to OXINARF for picking up the inconsistency with the previous logic
Change to user adjustable fusion of constant position (as per legacy EKF) instead of constant velocity.
Enable user to specify use of 3-axis magnetometer fusion when operating without aiding.
Don't allow gyro scale factor learning without external aiding data as it can be unreliable
- replace tabs with spaces
- remove C-style void from function arguments
- use pragma once
- fix pointer alignement
- remove unused header: AP_Airspeed_I2C_PX4 - we actually use
AP_Airspeed_PX4
This allows us to re-use SPIDevice from SPIDeviceDriver (the
to-become-SPIDeviceProperties) while the drivers are
converted. We create a fake device by calling the temporary
SPIDeviceManager::get_device() method passing the descriptor. The
transfer and assert logic is still using the old code.
Now we can interoperate SPIDeviceDriver with the ones based in
SPIDevice since they are going to use the same semaphore and bus.
The way this code is structured is a little bit different from the
SPIDriver implementation:
- We only open the bus once, no matter how many devices we have in it
- There's a single transfer() method which uses half-duplex mode
instead of full duplex. The reason is that for all cases in the
codebase we are using half-duplex transfers using the full-duplex
API, i.e. a single SPI msg with both tx and rx buffers. This is
cumbersome because the buffers need to be of the same size and the
receive buffer using an offset of the same length as the actux data
being written. This means the high level APIs need to copy buffers
around.
If later we have uses for a real full duplex case it's just a matter
of adding another transfer_fullduplex() method or something like
this.
- The methods are implemented in the SPIDevice class instead of having
proxy methods to SPIDeviceManager as is the case of SPIDriver
Also from now on we refer to the SPIDriver objects as "descriptors"
because they have the parameters of each device in the
SPIDeviceManager::devices[] table. When SPIDeviceDriver is completely
replaced we can rename them to SPIDeviceProperties.
Save in the manager the number of devices so it can be used in other
places like the SPIDevice implementation. This is a temporary storage
while we migrate to SPIDevice.
While at it use protected rather than private.
This allows us to re-use I2CDevice from I2CDriver while the drivers are
converted. We create a fake device with addr = 0 for each I2CDriver but
we only use the register/unregister logic. The transfer logic still uses
the methods from I2CDriver in order to use the right address.
Now we can interoperate I2CDevice drivers with the ones base in
I2CDriver since they are going to use the same semaphore and bus.
The I2CDriver constructors were changed to re-use the logic in I2CDevice
(it uses a number rather than an string) and the semaphore doesn't live
outside anymore, its embedded in the fake I2CDevice, as well as the
bus's file descritor.
This is a similar function to what we have in I2CDriver, but it can
receive a nullptr to recv or send. It will create 2 i2c_msg structs to
send and receive data to/from the I2C slave.
These are very similar to their counterparts in I2CDriver. The changes
were:
- Don't use fixed buffer with PATH_MAX length: allocate the string
- Change the interface to use std::vector so we can simplify the
implementation
This is very similar to std::unique_ptr, but doesn't require including
the <memory> header which pulls lots of c++ headers and cause problems
with nuttx headers. It's header-only. It contains an explanation on what
it solves, how to use and unit tests.
Add a cstddef header to allow using std::nullptr_t with those toolchains
that don't provide it. The idea is to make these platforms to use our
wrapper header (see https://gcc.gnu.org/onlinedocs/cpp/Wrapper-Headers.html)
and then we add the missing bits to the header.
Cast to the original type to use get function.
Still a hack but better than casting a pointer to an object which
memory mapping we are not supposed to know
Use pthread's barrier so we don't keep waking up threads with possibly
higher priority during initialization phase.
This also synchronizes all of them to a single point. With the previous
approach it was possible (but unlikely) that a thread hadn't reach the
synchronization point when main thread signalize "system initialized".
5hz update warnings are only valid if you have a fix, without a fix it adds load
to the GPS without any benefit. Our _5hz time messages are depenend upon GPS fix
time which isn't available yet
// @Description: When zero, the flare sink rate (TECS_LAND_SINK) is a fixed sink demand. With this enabled the flare sinkrate will increase/decrease the flare sink demand as you get further beyond the LAND waypoint. Has no effect before the waypoint. This value is added to TECS_LAND_SINK proportional to distance traveled after wp. With an increasing sink rate you can still land in a given distance if you're traveling too fast and cruise passed the land point. A positive value will force the plane to land sooner proportional to distance passed land point. A negative number will tell the plane to slowly climb allowing for a pitched-up stall landing. Recommend 0.2 as initial value.
Let the warning flag be added by the build system and not when/if the
header AP_Common.h is included. Both waf and make were already updated
to contain these warnings. Besides being in the wrong place, with
clang++ we actually can't add "-Wno-" definitions in build system
because we enable all of the in the header with -Wall.
The ublox driver will now continuosly poll for the settings from the GPS and correct any that are found to be in correct.
This status is then reported to the arming library as an additional arming check, allowing the user to be sure that the
gps is correctly configured before using it. If a user has a GPS2 configured that is not present they will fail the arming
checks until after they have disabled the second GPS.
2 new parameters were introduced as well:
-GPS_AUTO_CONFIG: Will not request any configuration packets to attempt to change them. (If the packet is recieved then
a update will be sent to it, but in testing this scenario never occured. This is set to 1 or 0 to change the setting.
(Defaults to 1 enabling auto config)
-GPS_GNSS_MODE2: Behaves the same way as GPS_GNSS_MODE but only applies to the second GPS.
GPS drivers are now allowed 2 seconds of non responsiveness before being unloaded
when a NMEA sentence is corrupted we should discard it
completely. This change prevents us considering a set of sentences
that includes corrupted sentences from being seen as new data
Reverse thrust for controlled landings, even with much steeper approach slopes. This is achieved by allowing throttle demand to go negative to maintain a target airspeed. A Pre-Flare stage was added, triggered by an altitude, to allow for a slower airspeed just before land. That lower airspeed can be near stall.
new params TECS_APPR_SMAX - sink rate max during approach
This is the only driver doing this, using the system_initializing() from
scheduler to log selectively. Remove the check together with removal of
unused wrapper methods to semaphore.
Due to the way the headers are organized changing a single change in
an AP_Notify driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.
Due to the way the headers are organized changing a single change in an
inertial sensor driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.
With this patch only AP_InertialSensor/AP_InertialSensor.h is exposed to
most users. There are some corner cases to integrate with some example
code, but most of the places now depend only on this header and this
header doesn't depend on the specific backends.
Now changing a single header, e.g. AP_InertialSensor_L3G4200D.h triggers
a rebuild only of these files:
$ waf copter
'copter' finished successfully (0.000s)
Waf: Entering directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
[ 80/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor.cpp
[ 84/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp
[310/370] Linking build/minlure/ArduCopter/libArduCopter_libs.a
[370/370] Linking build/minlure/bin/arducopter
Waf: Leaving directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
This is not used by any board and has a lot of commented out code. For
example, the compass is not enabled. The comment in the beginning of
the driver says it should serve as an example, but we should rather use
a working driver as an example. If this was at least a bit simpler and
that worked in the past we could refactor it to the new I2CDevice API.
This is not the case.
A string name allows to more easily expand the table: the board is
responsible for the name and doesn't have to declare it as a enum or
define. It's also easier to add 2 sensors of the same type.
This adds .data section loading to the HC-SR04 range finder driver used by
BBBMINI. The firmware is running inside a PRU. It is necessary to develop more
complex driver software inside the PRU.
This reverts support for RCInput via PWM. This is causing trouble in
some RPI-based boards, receiving a SIGSEGV. Let's revert it for now and
retry this later.
This reverts commit 5629f38b2c.
This reverts commit 51fd0b3d55.
This reverts commit 79d56073f7.
../../libraries/AP_HAL_Linux/RCInput_RPI.cpp: In member function ‘virtual void Linux::RCInput_RPI::_timer_tick()’:
../../libraries/AP_HAL_Linux/RCInput_RPI.cpp:489:127: warning: ‘x’ may be used uninitialized in this function [-Wmaybe-uninitialized]
counter = circle_buffer->bytes_available(curr_pointer, circle_buffer->get_offset(circle_buffer->_virt_pages, (uintptr_t)x));
^
This shrink must be used when the output camera sizes doesn't fit
the expected output.
We don't need to crop it even when the camera sizes aren't squared since
the shrink_8bpp() function shrinks a selected area.
This function shrinks a selected area on a 8bpp image.
The focus in this function was the performance, so this may not be the
clearer or the most understandable way to write it. The performance
was measured using GoogleBenchmark[1].
[1] - https://github.com/google/benchmark.git
Support for perf api using lttng.
Some additional build tricks needed for bebop because lttng uses dl_open
which is not compatible with a static link on a different libc as used
on the bebop
Sensor bias corrections were being applied to the incoming IMU data using the wrong delta time.
This was what was driving the different tuning between plane and copter for gyro bias process noise so the same gyro bias process noise default tuning value can now be used for all platform types.
Sensor bias corrections were being applied a a second time to the output observer inertial data.
Eliminate the use of horizontal position states during non-aiding operation to make it easier to tune.
Explicitly set the horizontal position associated Kalman gains to zero and the coresponding covariance entries to zero after avery fusion operation.
Make the horizontal velocity observation noise used during non-aiding operation adjustable.
Use a fixed value of velocity noise during initial alignment so that the flight peformance can be tuned without affecting the initial alignment.
We are not doing any dma here, it's just an SPI transaction. Name them
only rx/tx (although io_packet_tx/io_packet_rx could be another option).
This also zero-initialize the struct to keep valgrind happy about not
calling ioctl() with uninitialized variables.
This disables FRAM usage in PXF and erleboard. The reason is it's
failing and not being used. Right now we get this on startup:
root@beaglebone:~# ./ArduCopter.elf
FRAM: Online
Storage: FRAM is getting reset to default values
Failed to read FRAM
Testing with valgrind also reveals some invalid memory reads. Let's
disable it for now to be common with other boards.
This commit adds support for OpticalFlow to MinnowBoardMax trying to
leave the OpticalFlow implementation as generic as it already is.
We had to add some format conversion and software crop to the cameras that
do not have this features.
Most cameras do not support NV12 or GREY formats, we are adding in this commit
a conversion from YUYV format, that seems pretty common in cameras, to GREY
format (since we do not use Cb and Cr data on OpticalFlow).
Also we are adding a software crop for 8bpp images, such as GREY format. For
the same reason, most cameras do not have support for overlaying (crop, resize
and so on).
These functions are being added in order to be used in the next commits,
where we will add support for OpticalFlow on MinnowBoardMax.