34 #ifndef _uORBTest_UnitTest_hpp_ 35 #define _uORBTest_UnitTest_hpp_ 36 #include "../uORBCommon.hpp" 38 #include <px4_platform_common/time.h> 39 #include <px4_platform_common/tasks.h> 81 template<
typename S>
int latency_test(
orb_id_t T,
bool print);
88 UnitTest() : pubsubtest_passed(false), pubsubtest_print(false) {}
90 static int pubsubtest_threadEntry(
int argc,
char *argv[]);
91 int pubsublatency_main();
93 static int pub_test_multi2_entry(
int argc,
char *argv[]);
94 int pub_test_multi2_main();
100 int pubsubtest_res =
OK;
108 int test_multi_reversed();
109 int test_unadvertise();
115 static int pub_test_queue_entry(
int argc,
char *argv[]);
116 int pub_test_queue_main();
117 int test_queue_poll_notify();
118 volatile int _num_messages_sent = 0;
120 int test_fail(
const char *fmt, ...);
121 int test_note(
const char *fmt, ...);
127 test_note(
"---------------- LATENCY TEST ------------------");
134 if (pfd0 ==
nullptr) {
135 return test_fail(
"orb_advertise failed (%i)", errno);
138 char *
const args[1] = {
nullptr };
140 pubsubtest_print = print;
141 pubsubtest_passed =
false;
148 int pubsub_task = px4_task_spawn_cmd(
"uorb_latency",
156 while (!pubsubtest_passed) {
161 return test_fail(
"mult. pub0 timing fail");
168 if (pubsub_task < 0) {
169 return test_fail(
"failed launching task");
174 return pubsubtest_res;
177 #endif // _uORBTest_UnitTest_hpp_ static int pubsubtest_threadEntry(int argc, char *argv[])
volatile bool _thread_should_exit
int latency_test(orb_id_t T, bool print)
int info()
Print a little info about the driver.
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
void test(enum LPS25H_BUS busid)
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in p...
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
int orb_unadvertise(orb_advert_t handle)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).