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.
When there is already a driver registered on an i2c bus, the I2C_SLAVE ioctl
returns an error.
When it happens, it is better to display a warning and try to force the address.
It is especially useful on the bebop when killing the regular autopilot that uses
iio drivers to access the imu because else we would need to manually unbind the
driver in an init procedure.
I have added a warning because this error can also be resulting of another cause.
If the error is not EBUSY, then panic
If the I2C_SLAVE_FORCE ioctl fails then we panic because one of the i2c devices
won't be working properly.
This include some minor changes on all methods of PWM_Sysfs:
- Sort headers
- Add code inside Linux namespace rather than just use the namespace
- Declare a union pwm_params, that's only used to calculate at compile
time the maximum stack space we need in our methods: this is a bit
safer for future extensions
- Standardize error messages to include the useful params first and
then the error message
- Remove log message from hot path
- Don't abuse macros for checking error - convert the SNPRINTF_CHECK
macro into proper code, ignoring errors for not enough space since
they can't happen
- Fix call to read_file() passing uint8_t for "%u" in get_period()
- Fix passing char** instead of char* to write_file() in set_polarity()
- Use strncmp() instead of strncasecmp() since the kernel API uses
lowercase.
- Add comments on the 2 main methods of this class
With commit 24f4153 ("AP_HAL_Linux: RCOutput_PCA9685: group writes") a
log was introduced when we can't get the bus semaphore. However since we
are calling the non blocking method, failing there is not that unlikely
if the bus is shared. Return back to the previous behavior of not
logging.
prog_char and prog_char_t are now the same as char on supported
platforms. So, just change all places that use them and prefer char
instead.
AVR-specific places were not changed.
Now variables don't have to be declared with PROGMEM anymore, so remove
them. This was automated with:
git grep -l -z PROGMEM | xargs -0 sed -i 's/ PROGMEM / /g'
git grep -l -z PROGMEM | xargs -0 sed -i 's/PROGMEM//g'
The 2 commands were done so we don't leave behind spurious spaces.
AVR-specific places were not changed.
The PSTR is already define as a NOP for all supported platforms. It's
only needed for AVR so here we remove all the uses throughout the
codebase.
This was automated with a simple python script so it also converts
places which spans to multiple lines, removing the matching parentheses.
AVR-specific places were not changed.
ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp: In member
function 'int32_t Linux::Storage_FRAM::read(uint16_t, uint8_t*, uint16_t)':
/home/lucas/p/dronecode/ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp:183:24: war
ning: comparison is always false due to limited range of data type [-Wtype-limits]
if(Buff[i-fptr]==-1){
^
This commit adds the class Linux::GPIO_Sysfs. This class provides a generic
implementation of AP_HAL::GPIO on Linux by using GPIO Sysfs Interface
(https://www.kernel.org/doc/Documentation/gpio/sysfs.txt).
The channel() interface should be preferred in places that need to be
fast. Since it maintains the file descriptor open this is much faster
than opening and closing it.
We are using a microcontroller to read the PWM input from RC. The read
values are sent to our board using a simple serial protocol through the
UART interface.
This patch interprets these values and passes them forward to the APM.
Move the macros to a single place and reduce the variations not based on
board, but based on
- The name of the entry-point function, specified by AP_MAIN;
- Whether it contains argc/argv arguments or not.
The goal here is that programs (vehicles and examples) don't need to
include all possible boards to define a main function. Further patches
will change the programs.
Instead of requiring every program to specify the HAL related modules,
let the build system do it (in practice everything we compiled depended
on HAL anyway). This allow including only the necessary files in the
compilation.
The switching between different AP_HAL was happening by giving different
definitions of AP_HAL_BOARD_DRIVER, and the programs would use it to
instantiate.
A program or library code would have to explicitly include (and depend)
on the concrete implementation of the HAL, even when using it only via
interface.
The proposed change move this dependency to be link time. There is a
AP_HAL::get_HAL() function that is used by the client code. Each
implementation of HAL provides its own definition of this function,
returning the appropriate concrete instance.
Since this replaces the job of AP_HAL_BOARD_DRIVER, the definition was
removed.
The static variables for PX4 and VRBRAIN were named differently to avoid
shadowing the extern symbol 'hal'.
This warning happens because of the difference of datatypes between
32 and 64 bits processors.
%% libraries/AP_HAL_Linux/RCInput_UDP.o
/home/zehortigoza/dev/ardupilot/libraries/AP_HAL_Linux/RCInput_UDP.cpp: In member function 'virtual void Linux::LinuxRCInput_UDP::_timer_tick()':
/home/zehortigoza/dev/ardupilot/libraries/AP_HAL_Linux/RCInput_UDP.cpp:42:72: warning: format '%llu' expects argument of type 'long long unsigned int', but argument 3 has type 'uint64_t {aka long unsigned int}' [-Wformat=]
hal.console->printf("no rc cmds received for %llu\n", delay);
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
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.
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
It's possible to use the internal clock in PCA96895 if we account for
the drift it contains. This is a bit different from solutions in other
projects like the Adafruit library and the PX4 firmware: instead of
applying a correction to the final frequency we apply the correction to
the clock since this is the source of the error.
With this fix we arrived to much better results across different lots of
sensors.
The Navio board continues to use the external clock and should have no
difference behavior.
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
this makes it possible to bootup ardupilot before the desired network
interface is available. This is very useful for when using 3G dongles
in aircraft
The current implementation doesn't throw an error on a malformed path string.
i.e. udp:192.168.1.1.14550 instead of udp:192.168.1.1:14550 may result in a memory leak or whatsoever.
The commit fixes the issue and outputs a nice error message if anything's wrong.
DMA is getting stopped in the separate method now. This is the best we
can get at the current time. It does yield slightly better experience
and works in the majority of cases.
The patch is a no bulletproof solution, though.
There's a possibility of corruption in case of e.g. a SIGKILL. There's
no signal framework at the time and the commit doesn't add one. That's
why all signals are handled in the same erroneous way. This is not a
good nor a final solution to the issue.
For the issue at hand a better fix might be porting the code to kernel
space but it's a rather tediuos task that we cannot undertake in the
couple of weeks.
The issue has already come up. There's no deinitialization mechanisms at the moment. As APM is rather software than firmware on Linux, there're some clean-up work that needs to be done. This commit triggers deinitialization of RCInput on a panic.
Allowing to change the SPI device state allows us to save the
information whether the device was already initialized and avoid 2
separate drivers to initialize it.
The value for LINUX_STORAGE_SIZE was defined inconsistently against the one
defined for Linux boards in HAL_STORAGE_SIZE. That led to some values not
being written to the storage when running the test binary built at
libraries/StorageManager/examples/StorageTest.
The device number in /dev may not be reliable from one boot to another
due to the initialization order of each bus.
For example, in Minnow Board Max, the exposed I2C buses may be i2c-7 and
i2c-8 or i2c-8 and i2c-9 depending if the platform driver in the kernel
is initialized before or after the PCI.
It also may change with different version and configuration of the DT or
UEFI used making another kernel driver to bind to the device. This means that
for Minnow Board Max we need to use something like below to pass to the
constructor:
static const char * const i2c_devpaths[] = {
/* UEFI with lpss set to ACPI */
"/devices/platform/80860F41:05",
/* UEFI with lpss set to PCI */
"/devices/pci0000:00/0000:00:18.6",
NULL
};
The devpath here is the one returned by udev with the following command:
udevadm info -q path /dev/<i2c-device>
In contrary to the device number in /dev/i2c-N, this path in sysfs is
stable across reboots and can only change if there's a change in the
UEFI firmware or the board's device tree.
This patch assumes the currently supported boards don't have this
problem so it's not touching them.
Instead of hardcoding 8 as the limit for I2C msgs, use whatever the
kernel exported to us. In upstream this is 42 so it means we can group
together 21 addr/data pair instead of only 8.
All threads share the same address space and have the same pages locked
into memory so it's not necessary to call mlockall() for each of them.
Grepping /proc/<tid>/status gives the same VmLck for all of them, even
when only the main thread locks the memory:
# for i in `seq 477 482`; do \
name=$(cat /proc/$i/comm); \
vm=$(cat /proc/$i/status |grep VmLck); \
echo -e "$name\t$vm"; \
done
ArduCopter.elf VmLck: 57868 kB
sched-timer VmLck: 57868 kB
sched-uart VmLck: 57868 kB
sched-rcin VmLck: 57868 kB
sched-tonealarm VmLck: 57868 kB
sched-io VmLck: 57868 kB
Use pthread_setname_np() to set thread name so it's easier to debug
what't going on with each of them. This is the example output of the
relevant par of "ps -Leo class,rtprio,wchan,comm":
FF 12 futex_ ArduCopter.elf
FF 15 usleep sched-timer
FF 14 hrtime sched-uart
FF 13 poll_s sched-rcin
FF 11 hrtime sched-tonealarm
FF 10 hrtime sched-io
It's undefined behavior to pass the callback to pthread to a class
member like we were doing. Refactor the code so the callbacks are static
members.
This fixes the following warnings:
libraries/AP_HAL_Linux/Scheduler.cpp: In member function 'virtual void Linux::LinuxScheduler::init(void*)':
/home/lucas/p/dronecode/ardupilot/libraries/AP_HAL_Linux/Scheduler.cpp:61:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_timer_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:65:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_uart_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:69:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_rcin_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:73:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_tonealarm_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:77:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_io_thread);
LinuxScheduler::init() was not really working as it should. This was the
result of "ps -Leo class,rtprio,wchan,comm | grep ArduCopter":
FF 12 futex_ ArduCopter.elf
FF 12 usleep ArduCopter.elf
FF 12 hrtime ArduCopter.elf
FF 12 poll_s ArduCopter.elf
FF 12 hrtime ArduCopter.elf
FF 12 hrtime ArduCopter.elf
As can be seen all the threads run with the same priority, the one of the main
thread. There were basically 2 mistakes:
1) pthread_attr_setschedpolicy() needs to be called before
pthread_attr_setschedparam(). Otherwise the latter will just return
an error and not set the priority
2) pthread_create() defaults to ignore the priority and inherit the
it from the parent thread. pthread_attr_setinheritsched() needs to
be called to change the behavior to PTHREAD_EXPLICIT_SCHED. See
pthread_attr_setinheritsched(3) for an example program to test the
behaviors.
Also, it's undefined behavior to call pthread_attr_init() several times on the
same pthread_attr_t. Although we could reutilize the same attribute without
calling pthread_attr_init() again, lets refactor the code a little bit, so all
the pthread calls are in a single place. Then also call pthread_attr_destroy()
when we are done.
In Linux the default stack size is always greater than 32k, either 2MB
or 8MB depending on the architecture. There's no point in creating a
function to lock 32k.
Add support for /dev/spidev<bus>.<cs> in-kernel SPI CS handling, and convert
existing SPI devices over.
* Add a new member _subdev to the LinuxSPIDeviceDriver class, and initialiser
in LinuxSPIDevice constructor. Use subdev 0 for GPIO-managed CS
* Extend the _cs_pin to signed 16 bits and define SPI_CS_KERNEL (-1) for
kernel-managed CS
* Move to per-device file descriptors (required for in-kernel CS)
* Extend spidev filenames to include bus and subdevice numbers, possibly
longer than 1 digit each
* Allow support for platforms enumerating /dev/spidevNNN from non-zero bases
* Convert existing users over to the new API
Signed-off-by: John Williams <john@whelanwilliams.net>
ToneAlarm is now declared as a separate class instance of which is added as a private member of LinuxUtil
Some minor fixes in this patch include changing return type of tonealarm_init() to bool and use dprintf
exit from the autpilot when reboot is commanded.
The software assumes that the code is being
launched in an infinite loop thereby an exit
will make it reboot.
Preliminary support for Zynq/Linux on the 'ZyboPilot' HW platform.
see https://github.com/trjw/ZyboPilot-bsp for the PetaLinux / Vivado project
files.
At this stage CPPM/Pulse in and PWM out work, and in CLI mode the passthru
test works correctly.
The platform has passed minimal smoke testing in HIL mode.
ZYNQ IS NOT FLIGHT TESTED YET! FLY THIS PLATFORM AT YOUR OWN RISK!
Signed-off-by: John Williams <john@whelanwilliams.net>
Forthcoming Zynq port AP_HAL_Linux uses similar constants with different
values - move these as private member constants to avoid collisions.
Signed-off-by: John Williams <john@whelanwilliams.net>
When a S.Bus signal is fed into the rcin-Pin AruPlane on the BBB get's a
Segmentation fault. This patch prevents the memory acces to dsm_state.bytes[16] outside
of the array bounds. The patch should be reviewed by sombody who knows the DSM protocol,
as i don't.
Support for File System starage mode is retained, appropriate Storage
mode can be set by defining USE_FS_STORAGE for File System storage
aand US_FRAM_STORAGE for FRAM storage. Note: FS storage and FRAM
storage are never synced as of now.
This adds a check for trying to assert two CS pins on the same bus
at the same time. The change involves moving the _device handles into the
DeviceManager class, and accessing via static methods.
This also moves the semaphore to be per-bus rather than per-device,
which fixes the problem with bad MS5611 transfers.
Pair-Programmed-With: Victor, Sid, Anuj and Philip
add hal instance to generate scheduler
change gpio/export write method
add gpio struct to LinuxDigitalSource class
change individual gpio banks to one gpio_bank array
(credit to Mitch Miers <mmiers@mmiers.com>):
setup() is attempting to initialize the hardware, and while doing so
is attempting to output some text via the console (and maybe mavlink
data). The problem is, the output isn't going to complete once a
write buffer is full, because LinuxUARTDriver::_timer_tick() doesn't
perform work until _initialized is true. So, what happens is,
setup() (and subroutines) call LinuxUARTDriver::_write(uint8_t c),
which loops waiting for buffer space to become available (once the
write buffer is full). The buffer never gets space, because the
UART thread is waiting for initialization to complete before it
will write out data and drain the buffer, but that doesn't happen
until setup() returns (see AP_HAL_Linux_main.h).
Refer to https://groups.google.com/forum/#!topic/beaglepilot/dQlxse11JNI