AP_HAL_Linux: remove needless call to mlockall()
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
This commit is contained in:
parent
b7355dc62b
commit
f049c8e4c5
@ -259,8 +259,6 @@ void *LinuxScheduler::_timer_thread(void* arg)
|
|||||||
{
|
{
|
||||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||||
|
|
||||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
||||||
|
|
||||||
while (sched->system_initializing()) {
|
while (sched->system_initializing()) {
|
||||||
poll(NULL, 0, 1);
|
poll(NULL, 0, 1);
|
||||||
}
|
}
|
||||||
@ -304,8 +302,6 @@ void *LinuxScheduler::_rcin_thread(void *arg)
|
|||||||
{
|
{
|
||||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||||
|
|
||||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
||||||
|
|
||||||
while (sched->system_initializing()) {
|
while (sched->system_initializing()) {
|
||||||
poll(NULL, 0, 1);
|
poll(NULL, 0, 1);
|
||||||
}
|
}
|
||||||
@ -321,8 +317,6 @@ void *LinuxScheduler::_uart_thread(void* arg)
|
|||||||
{
|
{
|
||||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||||
|
|
||||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
||||||
|
|
||||||
while (sched->system_initializing()) {
|
while (sched->system_initializing()) {
|
||||||
poll(NULL, 0, 1);
|
poll(NULL, 0, 1);
|
||||||
}
|
}
|
||||||
@ -341,8 +335,6 @@ void *LinuxScheduler::_tonealarm_thread(void* arg)
|
|||||||
{
|
{
|
||||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||||
|
|
||||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
||||||
|
|
||||||
while (sched->system_initializing()) {
|
while (sched->system_initializing()) {
|
||||||
poll(NULL, 0, 1);
|
poll(NULL, 0, 1);
|
||||||
}
|
}
|
||||||
@ -359,8 +351,6 @@ void *LinuxScheduler::_io_thread(void* arg)
|
|||||||
{
|
{
|
||||||
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
LinuxScheduler* sched = (LinuxScheduler *)arg;
|
||||||
|
|
||||||
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
||||||
|
|
||||||
while (sched->system_initializing()) {
|
while (sched->system_initializing()) {
|
||||||
poll(NULL, 0, 1);
|
poll(NULL, 0, 1);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user