1 #ifndef PAL_STATISTICS_MSG_H 2 #define PAL_STATISTICS_MSG_H 11 #include <std_msgs/Header.h> 39 namespace serialization
44 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
46 stream.next(m.header);
48 stream.next(m.names_version);
55 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
57 stream.next(m.header);
58 stream.next(m.values);
59 stream.next(m.names_version);
79 static std::string temp =
"bece3d42a81d5c50cd68f110cf17bf55";
85 static std::unordered_set<std::string> temp = { getCompatibleKey() };
112 static std::string temp =
"44646896ace86f96c24fbb63054eeee8";
118 static std::unordered_set<std::string> temp = { getCompatibleKey() };
124 double timestamp)
override 132 if( _use_header_stamp )
134 timestamp = pal_msg.
header.stamp.toSec();
137 for(
size_t index = 0; index < pal_msg.
values.size(); index++)
139 if( index >=
values.size() )
141 values.emplace_back(
"placeholder" );
143 values[index].pushBack( { timestamp, pal_msg.
values[index] } );
149 for (
auto& it_version: _data)
152 auto& vect = it_version.second;
153 for (
size_t index = 0; index < vect.size(); index++ )
161 std::unordered_map<uint32_t, std::vector< PlotData > >
_data;
167 #endif // PAL_STATISTICS_MSG_H
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
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()
static std::unordered_map< uint32_t, std::vector< std::string > > _stored_pal_statistics_names
static void allInOne(Stream &stream, T m)
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
static void allInOne(Stream &stream, T m)
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