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