forked from Archive/PX4-Autopilot
fw pos ctl: make loop performance counter more meaningful
This commit is contained in:
parent
1faab673b2
commit
262b9fc754
|
@ -1399,8 +1399,6 @@ FixedwingPositionControl::task_main()
|
|||
continue;
|
||||
}
|
||||
|
||||
perf_begin(_loop_perf);
|
||||
|
||||
/* check vehicle control mode for changes to publication state */
|
||||
vehicle_control_mode_poll();
|
||||
|
||||
|
@ -1419,6 +1417,7 @@ FixedwingPositionControl::task_main()
|
|||
|
||||
/* only run controller if position changed */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
perf_begin(_loop_perf);
|
||||
|
||||
/* XXX Hack to get mavlink output going */
|
||||
if (_mavlink_fd < 0) {
|
||||
|
@ -1473,10 +1472,9 @@ FixedwingPositionControl::task_main()
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
perf_end(_loop_perf);
|
||||
}
|
||||
|
||||
perf_end(_loop_perf);
|
||||
}
|
||||
|
||||
_task_running = false;
|
||||
|
|
Loading…
Reference in New Issue