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