|
|
|
@ -52,7 +52,6 @@
@@ -52,7 +52,6 @@
|
|
|
|
|
uORB::DeviceMaster::DeviceMaster() |
|
|
|
|
{ |
|
|
|
|
px4_sem_init(&_lock, 0, 1); |
|
|
|
|
_last_statistics_output = hrt_absolute_time(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
uORB::DeviceMaster::~DeviceMaster() |
|
|
|
@ -178,15 +177,8 @@ int uORB::DeviceMaster::advertise(const struct orb_metadata *meta, bool is_adver
@@ -178,15 +177,8 @@ int uORB::DeviceMaster::advertise(const struct orb_metadata *meta, bool is_adver
|
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void uORB::DeviceMaster::printStatistics(bool reset) |
|
|
|
|
void uORB::DeviceMaster::printStatistics() |
|
|
|
|
{ |
|
|
|
|
hrt_abstime current_time = hrt_absolute_time(); |
|
|
|
|
PX4_INFO("Statistics, since last output (%i ms):", (int)((current_time - _last_statistics_output) / 1000)); |
|
|
|
|
_last_statistics_output = current_time; |
|
|
|
|
|
|
|
|
|
PX4_INFO("TOPIC, NR LOST MSGS"); |
|
|
|
|
bool had_print = false; |
|
|
|
|
|
|
|
|
|
/* Add all nodes to a list while locked, and then print them in unlocked state, to avoid potential
|
|
|
|
|
* dead-locks (where printing blocks) */ |
|
|
|
|
lock(); |
|
|
|
@ -199,23 +191,20 @@ void uORB::DeviceMaster::printStatistics(bool reset)
@@ -199,23 +191,20 @@ void uORB::DeviceMaster::printStatistics(bool reset)
|
|
|
|
|
|
|
|
|
|
if (ret != 0) { |
|
|
|
|
PX4_ERR("addNewDeviceNodes failed (%i)", ret); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
PX4_INFO_RAW("%-*s INST #SUB #Q SIZE PRIO PATH\n", (int)max_topic_name_length - 2, "TOPIC NAME"); |
|
|
|
|
|
|
|
|
|
cur_node = first_node; |
|
|
|
|
|
|
|
|
|
while (cur_node) { |
|
|
|
|
if (cur_node->node->print_statistics(reset)) { |
|
|
|
|
had_print = true; |
|
|
|
|
} |
|
|
|
|
cur_node->node->print_statistics(max_topic_name_length); |
|
|
|
|
|
|
|
|
|
DeviceNodeStatisticsData *prev = cur_node; |
|
|
|
|
cur_node = cur_node->next; |
|
|
|
|
delete prev; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!had_print) { |
|
|
|
|
PX4_INFO("No lost messages"); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, int &num_topics, |
|
|
|
@ -280,7 +269,6 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node,
@@ -280,7 +269,6 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node,
|
|
|
|
|
max_topic_name_length = name_length; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
last_node->last_lost_msg_count = last_node->node->lost_message_count(); |
|
|
|
|
last_node->last_pub_msg_count = last_node->node->published_message_count(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -387,11 +375,8 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
@@ -387,11 +375,8 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
|
|
|
|
|
cur_node = first_node; |
|
|
|
|
|
|
|
|
|
while (cur_node) { |
|
|
|
|
uint32_t num_lost = cur_node->node->lost_message_count(); |
|
|
|
|
unsigned int num_msgs = cur_node->node->published_message_count(); |
|
|
|
|
cur_node->pub_msg_delta = roundf((num_msgs - cur_node->last_pub_msg_count) / dt); |
|
|
|
|
cur_node->lost_msg_delta = roundf((num_lost - cur_node->last_lost_msg_count) / dt); |
|
|
|
|
cur_node->last_lost_msg_count = num_lost; |
|
|
|
|
cur_node->last_pub_msg_count = num_msgs; |
|
|
|
|
cur_node = cur_node->next; |
|
|
|
|
} |
|
|
|
@ -404,16 +389,16 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
@@ -404,16 +389,16 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
PX4_INFO_RAW(CLEAR_LINE "update: 1s, num topics: %i\n", num_topics); |
|
|
|
|
PX4_INFO_RAW(CLEAR_LINE "%-*s INST #SUB RATE #LOST #Q SIZE\n", (int)max_topic_name_length - 2, "TOPIC NAME"); |
|
|
|
|
PX4_INFO_RAW(CLEAR_LINE "%-*s INST #SUB RATE #Q SIZE\n", (int)max_topic_name_length - 2, "TOPIC NAME"); |
|
|
|
|
cur_node = first_node; |
|
|
|
|
|
|
|
|
|
while (cur_node) { |
|
|
|
|
|
|
|
|
|
if (!print_active_only || (cur_node->pub_msg_delta > 0 && cur_node->node->subscriber_count() > 0)) { |
|
|
|
|
PX4_INFO_RAW(CLEAR_LINE "%-*s %2i %4i %4i %5i %2i %4i \n", (int)max_topic_name_length, |
|
|
|
|
PX4_INFO_RAW(CLEAR_LINE "%-*s %2i %4i %4i %2i %4i \n", (int)max_topic_name_length, |
|
|
|
|
cur_node->node->get_meta()->o_name, (int)cur_node->node->get_instance(), |
|
|
|
|
(int)cur_node->node->subscriber_count(), cur_node->pub_msg_delta, |
|
|
|
|
(int)cur_node->lost_msg_delta, cur_node->node->get_queue_size(), cur_node->node->get_meta()->o_size); |
|
|
|
|
cur_node->node->get_queue_size(), cur_node->node->get_meta()->o_size); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
cur_node = cur_node->next; |
|
|
|
|