forked from Archive/PX4-Autopilot
Fixed PPM warning to be only printed with PPM inputs enabled
This commit is contained in:
parent
9e72e72644
commit
6a40acdbdc
|
@ -1810,7 +1810,7 @@ PX4IO::print_status()
|
|||
|
||||
printf("\n");
|
||||
|
||||
if (raw_inputs > 0) {
|
||||
if ((flags & PX4IO_P_STATUS_FLAGS_RC_PPM)) {
|
||||
int frame_len = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_RC_DATA);
|
||||
printf("RC data (PPM frame len) %u us\n", frame_len);
|
||||
|
||||
|
|
Loading…
Reference in New Issue