Go to the documentation of this file.00001 #include <swri_profiler_tools/profiler_msg_adapter.h>
00002 #include <swri_profiler_tools/util.h>
00003
00004 namespace swri_profiler_tools
00005 {
00006 ProfilerMsgAdapter::ProfilerMsgAdapter()
00007 {
00008 }
00009
00010 ProfilerMsgAdapter::~ProfilerMsgAdapter()
00011 {
00012 }
00013
00014 void ProfilerMsgAdapter::processIndex(const swri_profiler_msgs::ProfileIndexArray &msg)
00015 {
00016 const QString ros_node_name =
00017 normalizeNodePath(QString::fromStdString(msg.header.frame_id));
00018
00019
00020
00021
00022 index_[ros_node_name].clear();
00023
00024 for (auto const &item : msg.data) {
00025 QString label = normalizeNodePath(QString::fromStdString(item.label));
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 if (!label.startsWith(ros_node_name)) {
00037 label = ros_node_name + label;
00038 }
00039
00040
00041 index_[ros_node_name][item.key] = label;
00042 }
00043 }
00044
00045 bool ProfilerMsgAdapter::processData(
00046 NewProfileDataVector &out_data,
00047 const swri_profiler_msgs::ProfileDataArray &msg)
00048 {
00049 const QString node_name(QString::fromStdString(msg.header.frame_id));
00050
00051 if (index_.count(node_name) == 0) {
00052 qWarning("No index for node '%s'. Dropping data update.", qPrintable(node_name));
00053 return false;
00054 }
00055
00056 int timestamp_sec = std::round(msg.header.stamp.toSec());
00057
00058 NewProfileDataVector out;
00059 out.reserve(msg.data.size());
00060 for (auto const &item : msg.data) {
00061 if (index_[node_name].count(item.key) == 0) {
00062 qWarning("No index for block %d of %s. Dropping all data "
00063 "because index is probably invalid.",
00064 item.key, qPrintable(node_name));
00065 return false;
00066 }
00067
00068 out.emplace_back();
00069 out.back().label = index_[node_name][item.key];
00070 out.back().wall_stamp_sec = timestamp_sec;
00071 out.back().ros_stamp_ns = msg.rostime_stamp.toNSec();
00072 out.back().cumulative_call_count = item.abs_call_count;
00073 out.back().cumulative_inclusive_duration_ns = item.abs_total_duration.toNSec();
00074 out.back().incremental_inclusive_duration_ns = item.rel_total_duration.toNSec();
00075 out.back().incremental_max_duration_ns = item.rel_max_duration.toNSec();
00076 }
00077
00078 out_data.insert(out_data.end(), out.begin(), out.end());
00079 return true;
00080 }
00081
00082 void ProfilerMsgAdapter::reset()
00083 {
00084 index_.clear();
00085 }
00086 };