39 #include <px4_platform_common/px4_config.h> 41 #include <sys/types.h> 50 #include <arch/board/board.h> 76 PX4_INFO(
"Reading PPM values - press any key to abort");
77 PX4_INFO(
"This test guarantees: 10 Hz update rates, no glitches (channel values), no channel count changes.");
91 fds[0].events = POLLIN;
93 fds[1].events = POLLIN;
97 int ret = poll(fds, 2, 200);
101 if (fds[0].revents & POLLIN) {
108 PX4_ERR(
"comparison fail: RC: %d, expected: %d", rc_input.
values[i], rc_last.
values[i]);
123 PX4_ERR(
"TIMEOUT, less than 10 Hz updates");
137 PX4_ERR(
"failed reading RC input data");
141 PX4_INFO(
"PPM CONTINUITY TEST PASSED SUCCESSFULLY!");
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
High-resolution timer with callouts and timekeeping.
int orb_subscribe(const struct orb_metadata *meta)
int test_rc(int argc, char *argv[])
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
int orb_unsubscribe(int handle)
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
int orb_check(int handle, bool *updated)
Dual< Scalar, N > abs(const Dual< Scalar, N > &a)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).