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.