|
|
@ -49,77 +49,111 @@ extern "C" __EXPORT int listener_main(int argc, char *argv[]); |
|
|
|
|
|
|
|
|
|
|
|
static void usage(); |
|
|
|
static void usage(); |
|
|
|
|
|
|
|
|
|
|
|
void listener(listener_print_topic_cb cb, const orb_id_t &id, unsigned num_msgs, unsigned topic_instance, |
|
|
|
void listener(listener_print_topic_cb cb, const orb_id_t &id, unsigned num_msgs, int topic_instance, |
|
|
|
unsigned topic_interval) |
|
|
|
unsigned topic_interval) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (orb_exists(id, topic_instance) != 0) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("never published\n"); |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int sub = orb_subscribe_multi(id, topic_instance); |
|
|
|
if (topic_instance == -1 && num_msgs == 1) { |
|
|
|
orb_set_interval(sub, topic_interval); |
|
|
|
// first count the number of instances
|
|
|
|
|
|
|
|
int instances = 0; |
|
|
|
|
|
|
|
|
|
|
|
bool updated = false; |
|
|
|
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { |
|
|
|
unsigned i = 0; |
|
|
|
if (orb_exists(id, i) == PX4_OK) { |
|
|
|
hrt_abstime start_time = hrt_absolute_time(); |
|
|
|
instances++; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
while (i < num_msgs) { |
|
|
|
if (instances == 1) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("\nTOPIC: %s\n", id->o_name); |
|
|
|
|
|
|
|
int sub = orb_subscribe(id); |
|
|
|
|
|
|
|
cb(id, sub); |
|
|
|
|
|
|
|
orb_unsubscribe(sub); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else if (instances > 1) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("\nTOPIC: %s %d instances\n", id->o_name, instances); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { |
|
|
|
|
|
|
|
if (orb_exists(id, i) == PX4_OK) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("\nInstance %d:\n", i); |
|
|
|
|
|
|
|
int sub = orb_subscribe_multi(id, i); |
|
|
|
|
|
|
|
cb(id, sub); |
|
|
|
|
|
|
|
orb_unsubscribe(sub); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// check for user input to quit
|
|
|
|
} else { |
|
|
|
int user_input_timeout = 1; |
|
|
|
if (orb_exists(id, topic_instance) != 0) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("never published\n"); |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
orb_check(sub, &updated); |
|
|
|
int sub = orb_subscribe_multi(id, topic_instance); |
|
|
|
|
|
|
|
orb_set_interval(sub, topic_interval); |
|
|
|
|
|
|
|
|
|
|
|
if (i == 0) { |
|
|
|
bool updated = false; |
|
|
|
updated = true; |
|
|
|
unsigned i = 0; |
|
|
|
user_input_timeout = 0; // don't wait
|
|
|
|
hrt_abstime start_time = hrt_absolute_time(); |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// check for user input
|
|
|
|
while (i < num_msgs) { |
|
|
|
struct pollfd fds {}; |
|
|
|
|
|
|
|
fds.fd = 0; /* stdin */ |
|
|
|
|
|
|
|
fds.events = POLLIN; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (poll(&fds, 1, 0) > 0) { |
|
|
|
// check for user input to quit
|
|
|
|
|
|
|
|
int user_input_timeout = 1; |
|
|
|
|
|
|
|
|
|
|
|
char c = 0; |
|
|
|
orb_check(sub, &updated); |
|
|
|
int ret = read(0, &c, user_input_timeout); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (ret) { |
|
|
|
if (i == 0) { |
|
|
|
return; |
|
|
|
updated = true; |
|
|
|
|
|
|
|
user_input_timeout = 0; // don't wait
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
switch (c) { |
|
|
|
// check for user input
|
|
|
|
case 0x03: // ctrl-c
|
|
|
|
struct pollfd fds {}; |
|
|
|
case 0x1b: // esc
|
|
|
|
fds.fd = 0; /* stdin */ |
|
|
|
case 'q': |
|
|
|
fds.events = POLLIN; |
|
|
|
return; |
|
|
|
|
|
|
|
/* not reached */ |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (updated) { |
|
|
|
if (poll(&fds, 1, 0) > 0) { |
|
|
|
start_time = hrt_absolute_time(); |
|
|
|
|
|
|
|
i++; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
PX4_INFO_RAW("\nTOPIC: %s instance %d #%d\n", id->o_name, topic_instance, i); |
|
|
|
char c = 0; |
|
|
|
|
|
|
|
int ret = read(0, &c, user_input_timeout); |
|
|
|
|
|
|
|
|
|
|
|
int ret = cb(id, sub); |
|
|
|
if (ret) { |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (ret != PX4_OK) { |
|
|
|
switch (c) { |
|
|
|
PX4_ERR("listener callback failed (%i)", ret); |
|
|
|
case 0x03: // ctrl-c
|
|
|
|
|
|
|
|
case 0x1b: // esc
|
|
|
|
|
|
|
|
case 'q': |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
/* not reached */ |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
if (updated) { |
|
|
|
if (hrt_elapsed_time(&start_time) > 2 * 1000 * 1000) { |
|
|
|
start_time = hrt_absolute_time(); |
|
|
|
PX4_INFO_RAW("Waited for 2 seconds without a message. Giving up.\n"); |
|
|
|
i++; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
PX4_INFO_RAW("\nTOPIC: %s instance %d #%d\n", id->o_name, topic_instance, i); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int ret = cb(id, sub); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (ret != PX4_OK) { |
|
|
|
|
|
|
|
PX4_ERR("listener callback failed (%i)", ret); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
if (hrt_elapsed_time(&start_time) > 2 * 1000 * 1000) { |
|
|
|
|
|
|
|
PX4_INFO_RAW("Waited for 2 seconds without a message. Giving up.\n"); |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
orb_unsubscribe(sub); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
orb_unsubscribe(sub); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
int listener_main(int argc, char *argv[]) |
|
|
|
int listener_main(int argc, char *argv[]) |
|
|
@ -131,7 +165,7 @@ int listener_main(int argc, char *argv[]) |
|
|
|
|
|
|
|
|
|
|
|
char *topic_name = argv[1]; |
|
|
|
char *topic_name = argv[1]; |
|
|
|
|
|
|
|
|
|
|
|
unsigned topic_instance = 0; |
|
|
|
int topic_instance = -1; |
|
|
|
unsigned topic_rate = 0; |
|
|
|
unsigned topic_rate = 0; |
|
|
|
unsigned num_msgs = 0; |
|
|
|
unsigned num_msgs = 0; |
|
|
|
|
|
|
|
|
|
|
|