../../libraries/AP_HAL_Linux/Perf.cpp: In member function ‘void Linux::Perf::_debug_counters()’:
../../libraries/AP_HAL_Linux/Perf.cpp:85:36: warning: format ‘%llu’ expects argument of type ‘long long unsigned int’, but argument 4 has type ‘uint64_t {aka long unsigned int}’ [-Wformat=]
c.name, c.count);
^
Test code for integration with another thread to pull data from internal
perf counters. Since we are using the timer thread here, there's no
retry mechanism and we only print that data can be corrupted.
Instead of creating a new object Perf_Lttng copying the necessaries
fields, just make a tighter integration with the internal perf counters
and re-use the same fields.
The idea is to leave the internal perf enabled all the time, like it is
in PX4, and then allow the integration with lttng on top. Next step
would be to runtime enable/disable only the perf counters we are
interested in.
This also changes the structure so it's easy to allow another thread to
pull data from the Perf object. A rw lock protects from addition of new
counters and an atomic unsigned int allows other threads to do a
lockless copy of the data.
In order for this to work the allocation was changed to use a single
memory pool instead of returning a calloc'ed data for each perf counter.
Since most of our counters are of ' elapsed' type, don't bother using a
smaller struct for the 'count' type
If the RPi version detection fails, the standard version is now RPi2/3 instead of RPi1.
I think this is useful, because the RPi1 is not really supported (performance reasons).
Like others, use HAVE_ prefix and name it HAVE_LTTNG_UST to be the same
name as exported by pkg-config While at it remove wrong comment with
_HELLO_TP_H.
Implementation of alloca() is very much architecture and compiler
dependent. Avoid the case in which it could return a non-aligned
pointer, which would mean Thread::_poison_stack() would do the wrong
thing.
../../libraries/AP_HAL_Linux/Thread.cpp: In member function ‘void Linux::Thread::_poison_stack()’:
../../libraries/AP_HAL_Linux/Thread.cpp:63:20: warning: declaration of ‘start’ shadows a member of 'this' [-Wshadow]
uint8_t *end, *start, *curr;
^
Sort include alphabetically and make them in order:
Main header
system headers
library headers
local headers
While reordering, change a include of endian.h to our sparse-endian.h
which is more reliant to toolchain changes.
Running the vehicles we check the stack size doesn't grow too much by
enabling the DEBUG_STACK in the scheduler. Even on 64bit boards the
stack is consistent around 4k. Just to be a little conservative, let it
be a little bit more that that: 256kB.
Since we have RT prio and we call mlock(), the memory for the stack of
each thread is locked in memory. This means we are effectively taking
that much memory. The default stack size varies per distro, but it's
common to have 8MB for 64 bit boards and 4MB for 32 bit boards. Here is
the output of ps -L -o 'comm,rtprio,rss $(pidof arducopter-quad)', showing the
RSS of arducopter-quad before and after this change:
Before:
COMMAND RTPRIO RSS
arducopter-quad 12 46960
sched-timer 15 46960
sched-uart 14 46960
sched-rcin 13 46960
sched-tonealarm 11 46960
sched-io 10 46960
After:
COMMAND RTPRIO RSS
arducopter-quad 12 7320
sched-timer 15 7320
sched-uart 14 7320
sched-rcin 13 7320
sched-tonealarm 11 7320
sched-io 10 7320
We don't need all the comments in the array declaration and we can
inline its declaration in the function call. This makes it easier to
copy it to other places.
This bug led to issues for us so it may help others to resolve it.
Currently, the AP_HAL_Linux RCInput::read(uint16_t*,uint8_t) function
only returns the first x nonzero channels. Once it hits a channel that
is set to zero, it stops and all remaining channels are returned as
zero, even if they are set. This causes discrepancies between the raw RC
input sent to the GCS and the RC input that is actually used on the
vehicle.
The fixes this issue and makes it behave exactly as it does on the
PX4_HAL code. We ran into this issue when sending rc_override messages
in which there were some channels set to zero.
0-length arrays are supported in C but forbidden in C++. GCC allows it
but clang is more strict:
../../libraries/AP_HAL_Linux/SPIDriver.cpp:75:35: fatal error: no matching constructor for initialization of 'Linux::SPIDeviceDriver [0]'
SPIDeviceDriver SPIDeviceManager::_device[0];
^
../../libraries/AP_HAL_Linux/SPIDriver.h:20:7: note: candidate constructor (the implicit move constructor) not viable: requires 1 argument, but 0 were provided
class SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
^
../../libraries/AP_HAL_Linux/SPIDriver.h:20:7: note: candidate constructor (the implicit copy constructor) not viable: requires 1 argument, but 0 were provided
../../libraries/AP_HAL_Linux/SPIDriver.h:25:5: note: candidate constructor not viable: requires 9 arguments, but 0 were provided
SPIDeviceDriver(const char *name, uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
^
1 error generated.
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
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".
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 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
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.
This reverts commit 8cca0beba9.
The PWM input using the RPI DMA is causing trouble with RPI boards using
PPMSUM. Let's revert it until the solution is found. We still leave the
ifdef in RCInput for BH hat.
The initial idea was to export all pins to be used at once, so we
created _export_pins() to take all of them and a wrapper method,
_export_pin() to export a single one. However we never export more than
one pin at once.
- Replaced PATH_MAX by the maximum stack memory it will use for GPIO
paths
- Added more information to error logs
- Removed the '/n' when writing to GPIO sysfs files
- Using Linux Util write_file() on _pinMode()
Make sure pinMode() method exports the pin before using it. Otherwise
the export method would need to be called, differently from other GPIO
implementations.
Since now export_pin and export_pins are called only internally, reduce
their visibility to protected.
These errors were all over the VideoIn.cpp file:
libraries/AP_HAL_Linux/VideoIn.cpp: In member function 'bool Linux::VideoIn::allocate_buffers(uint32_t)':
libraries/AP_HAL_Linux/VideoIn.cpp:107:15: error: invalid conversion from 'uint32_t {aka unsigned int}' to 'v4l2_memory' [-fpermissive]
rb.memory = _memtype;
^
libraries/AP_HAL_Linux/VideoIn.cpp: In member function 'bool Linux::VideoIn::set_format(uint32_t*, uint32_t*, uint32_t*, uint32_t*, uint32_t*)':
libraries/AP_HAL_Linux/VideoIn.cpp:169:14: error: invalid conversion from 'int' to 'v4l2_buf_type' [-fpermissive]
fmt.type = V4L2_CAP_VIDEO_CAPTURE;
^
Add proper casts to fix the compilation.
Let it be a static const member instead of defining it in a header. The
problem with the header is that it will generate conflicting symbols
when more than 1 compilation unit includes it.
- Remove commented out defines
- Sort headers
- Remove ifdef for HAL_BOARD_SUBTYPE_LINUX_BEBOP inside the same ifdef
- Use AP_HAL::panic() instead of perror
- AP_HAL::panic() message doesn't take a '\n' and there's no return
statement after a call to this function
- Fix pointer placement
- Use pragma once
- Don't initialize members to 0, it's already the default behavior of
our custom allocator
Implementation of AP_HAL::OpticalFlow for an embedded camera sensor
There is the possibility to record video and also the gyro datas in order
to process the video off-board and debug possible issues.
Implementation of the PX4 flow algorithm for ardupilot.
Based on the original PX4 Flow code, it has diverged a lot.
I have kept the license header since it is required.
I have removed all the unused and dead code on current implementation,
modified the code to make it clearer, re-indented it and changed
the way some params are calculated. It has been tested on PC and
on board and showed results that I assumed were OK. No optical flow
Loiter tests have been undertaken since it requires a Sonar which will
be added soon.
Limitations :
Some parts were written in ARM assembly and I rewrote them very naively
to get them to be more easily portable. A simple optimisation would be
to re-introduce assembly code for ARM as a separate asm file with
methods for fixed resolutions that would reduce a lot the amount of
calculation and memory read/writes. Then writing a version in NEON
assembly would even be more optimised and then maybe an Intel version.
- No need to if/else if just returning
- Sort includes
- Fix missing space in log message
- When closing the fd, set it to -1. It's better to later fail the
operation than to operate on another random file descriptor
- Add some spaces to improve readability
- Use pragma once
- Do not initialize members to zero, it's already the behavior for our
custom allocator
VideoIn class is created that allows to setup a v4l2 interface
and capture buffers. I is based on yavta utility by Laurent Pinchart
and has been tested only on the bebop, though yavta works on any linux
platform.
- Replace tabs with spaces
- Sort includes
- No need to ifdef Linux inside AP_HAL_Linux
- Use early returns on error rather than a chain o if/else
- Use pragma once
- No need to initialize class members to 0, it's already our default
behavior
The camera sensor is connected on i2c bus for config
and on a parallel bus on the main SoC.
Currently, the i2c driver remains userland, but this is intended to
change in the future. The v4l2_subdev part is the way to go in the future
and it is the mainline way of configuring i2c camera sensors on Linux.
Currently only the max framerate is supported because it is the one that
is to be used on the bebop optical flow.
Newer esc firmware versions on bebop 1 and all the versions on bebop 2
have a different order for the motors in the i2c frame sent to the
esc contoller. This commit adds support for both versions by reading
the firmware version of the esc, using GET_INFO frame
This was previously used to allow to save a state in a SPIDriver so we
could synchronize the initialization of AP_Compass and
AP_InertialSensor.
It was only used by MPU9250 and is not used anymore since the move to
AuxiliaryBus initialization and it's not used anymore since c3dae6f
("AP_InertialSensor: MPU9250: Remove methods not used anymore")
As commented in 8218140 ("AP_Common: add scanf format macro"), "FORMAT"
was a bad name for this macro since there's also the scanf. Rename to
FMT_PRINTF to follow the scanf name.
Only compiled on Bebop, the constructor will need to be modified to
pass the pwm chip number and to create a PWM_Sysfs instead of a PWM_Sysfs_Bebop
in case it is used on a mainline linux board
- Make error path in constructor shorter and earlier. It's calling
panic() so there's no reason to do anything else
- We don't need to check variable for NULL when calling free()
- Change set/get_polarity to use a virtual function; this allows us
not to fail silently if _polarity_path is NULL for PWM_Sysfs.
PWM_Sysfs_Bebop just overrides this method and implement an empty
version.
Modify existing class to create a PWM_Sysfs_Base class and derive it for
Bebop and Pwm_Sysfs (mainline kernel)
use asprintf for path allocation since it doesn't cost so much and is done
only at startup
Note that the constructor of the 2 classes : PWM_Sysfs and PWM_Sysfs_Bebop
allocate the paths and the constructor and desctuctor of class PWM_Sysfs_Base
frees them.
only keep in memory the paths that are needed later, i.e free _export_path,
_duty_path. The remaining path are freed in the destructor
Implement the new AP_HAL functions and use them in the Scheduler when
possible.
The '_sketch_start_time' was renamed and moved as a detail of
implementation of the functions code. It allows the code to return time
starting from zero.
The 'stopped_clock_usec' was renamed to follow convention in the file
and add a getter so that AP_HAL functions can reach it. It's not a
problem this getter is public because in practice, regular code
shouldn't even access the Linux::Scheduler directly -- only code that
should is from Linux implementation.
For certain basic functionality, there aren't much benefit to be able to
vary the implementation easily at runtime. So instead of using virtual
functions, use regular functions that are "resolved" at link time. The
implementation of such functions is provided per board/platform.
Examples of functions that fit this include: getting the current
time (since boot), panic'ing, getting system information, rebooting.
These functions are less likely to benefit from the indirection provided
by virtual interfaces. For more complex hardware access APIs the
indirection makes more sense and ease the testing (when we have it!).
The idea is that instead of calling
hal.scheduler->panic("on the streets of london");
now use
AP_HAL::panic("on the streets of london");
A less important side-effect is that call-site code gets
smaller. Currently the compiler needs to get the hal, get the scheduler
pointer, get the right function pointer in the vtable for that
scheduler. And the call must include an extra parameter ("this"). Now it
will be just a function call, with the address resolved at link time.
This patch introduces the first functions that will be in the namespace,
further patches will implementations for each board and then switch the
call-sites. The extra init() function allow any initial setup needed for
the functions to work.