pal_statistics_msg.h
Go to the documentation of this file.
1 #ifndef PAL_STATISTICS_MSG_H
2 #define PAL_STATISTICS_MSG_H
3 
4 #include <string>
5 #include <vector>
6 #include <map>
7 
8 #include <ros/types.h>
9 #include <ros/serialization.h>
10 #include "ros_parser_base.h"
11 #include <std_msgs/Header.h>
12 #include <absl/strings/str_cat.h>
13 #include <absl/strings/charconv.h>
14 
16 {
17 // Header header
18 // string[] names
19 // uint32 names_version #This is increased each time names change
20  std_msgs::Header header;
21  std::vector<std::string> names;
22  uint32_t names_version;
23 };
24 
26 {
27 // Header header
28 // float64[] names
29 // uint32 names_version #This is increased each time names change
30  std_msgs::Header header;
31  std::vector<double> values;
32  uint32_t names_version;
33 };
34 
35 //-----------------------------------------------------
36 
37 namespace ros
38 {
39 namespace serialization
40 {
41 
42 template<> struct Serializer< ::PalStatisticsNames_ >
43 {
44  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
45  {
46  stream.next(m.header);
47  stream.next(m.names);
48  stream.next(m.names_version);
49  }
51 };
52 
53 template<> struct Serializer< ::PalStatisticsValues_ >
54 {
55  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
56  {
57  stream.next(m.header);
58  stream.next(m.values);
59  stream.next(m.names_version);
60  }
62 };
63 
64 } // namespace serialization
65 } // namespace ros
66 
67 //-----------------------------------------------------
68 
69 static std::unordered_map<uint32_t, std::vector<std::string> > _stored_pal_statistics_names;
70 
72 {
73 public:
74 
75  PalStatisticsNamesParser() = default;
76 
77  static const std::string& getCompatibleKey()
78  {
79  static std::string temp = "bece3d42a81d5c50cd68f110cf17bf55";
80  return temp;
81  }
82 
83  const std::unordered_set<std::string>& getCompatibleKeys() const override
84  {
85  static std::unordered_set<std::string> temp = { getCompatibleKey() };
86  return temp;
87  }
88 
89  virtual void pushMessageRef(const std::string& ,
90  const MessageRef& msg,
91  double) override
92  {
93  PalStatisticsNames_ pal_names;
94  ros::serialization::IStream is( const_cast<uint8_t*>(msg.data()), msg.size() );
95  ros::serialization::deserialize(is, pal_names);
96  _stored_pal_statistics_names.insert( {pal_names.names_version, std::move(pal_names.names) });
97  }
98 
99  void extractData(PlotDataMapRef& , const std::string& ) override
100  { }
101 };
102 
103 //-----------------------------------------------------
105 {
106 public:
107 
108  PalStatisticsValuesParser() = default;
109 
110  static const std::string& getCompatibleKey()
111  {
112  static std::string temp = "44646896ace86f96c24fbb63054eeee8";
113  return temp;
114  }
115 
116  const std::unordered_set<std::string>& getCompatibleKeys() const override
117  {
118  static std::unordered_set<std::string> temp = { getCompatibleKey() };
119  return temp;
120  }
121 
122  virtual void pushMessageRef(const std::string& ,
123  const MessageRef& msg,
124  double timestamp) override
125  {
126  PalStatisticsValues_ pal_msg;
127  ros::serialization::IStream is( const_cast<uint8_t*>(msg.data()), msg.size() );
128  ros::serialization::deserialize(is, pal_msg);
129 
130  auto& values = _data[ pal_msg.names_version ];
131 
132  if( _use_header_stamp )
133  {
134  timestamp = pal_msg.header.stamp.toSec();
135  }
136 
137  for( size_t index = 0; index < pal_msg.values.size(); index++)
138  {
139  if( index >= values.size() )
140  {
141  values.emplace_back( "placeholder" );
142  }
143  values[index].pushBack( { timestamp, pal_msg.values[index] } );
144  }
145  }
146 
147  void extractData(PlotDataMapRef& plot_map, const std::string& prefix) override
148  {
149  for ( auto& it_version: _data)
150  {
151  const auto& names = _stored_pal_statistics_names[ it_version.first ];
152  auto& vect = it_version.second;
153  for ( size_t index = 0; index < vect.size(); index++ )
154  {
155  appendData(plot_map, absl::StrCat(prefix, "/", names.at(index) ), vect[index]);
156  }
157  }
158  }
159 
160 private:
161  std::unordered_map<uint32_t, std::vector< PlotData > > _data;
162 
163 };
164 
165 
166 
167 #endif // PAL_STATISTICS_MSG_H
std_msgs::Header header
std::vector< double > values
#define ROS_DECLARE_ALLINONE_SERIALIZER
std::string StrCat(const AlphaNum &a, const AlphaNum &b)
void extractData(PlotDataMapRef &, const std::string &) override
size_t size() const
void extractData(PlotDataMapRef &plot_map, const std::string &prefix) override
std::vector< std::string > names
std::unordered_map< uint32_t, std::vector< PlotData > > _data
const std::unordered_set< std::string > & getCompatibleKeys() const override
static const std::string & getCompatibleKey()
std_msgs::Header header
static std::unordered_map< uint32_t, std::vector< std::string > > _stored_pal_statistics_names
static const std::string & getCompatibleKey()
const uint8_t * data() const
std::vector< double > values
virtual void pushMessageRef(const std::string &, const MessageRef &msg, double timestamp) override
const std::unordered_set< std::string > & getCompatibleKeys() const override
void deserialize(Stream &stream, T &t)
virtual void pushMessageRef(const std::string &, const MessageRef &msg, double) override


plotjuggler
Author(s): Davide Faconti
autogenerated on Sat Jul 6 2019 03:44:17