forked from Archive/PX4-Autopilot
perf_counter: fixed write to correct fd for perf output
this fixes perf output for nsh over MAVLink
This commit is contained in:
parent
aa1d7d7869
commit
4eaa18e6f9
|
@ -377,7 +377,7 @@ perf_reset(perf_counter_t handle)
|
|||
void
|
||||
perf_print_counter(perf_counter_t handle)
|
||||
{
|
||||
perf_print_counter_fd(0, handle);
|
||||
perf_print_counter_fd(1, handle);
|
||||
}
|
||||
|
||||
void
|
||||
|
|
Loading…
Reference in New Issue