ros1_parsers/twist_msg.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <geometry_msgs/Twist.h>
4 #include <geometry_msgs/TwistStamped.h>
5 #include <geometry_msgs/TwistWithCovariance.h>
6 #include "quaternion_msg.h"
7 #include "ros1_parser.h"
8 #include "header_msg.h"
9 
10 class TwistMsgParser : public BuiltinMessageParser<geometry_msgs::Twist>
11 {
12 public:
13  TwistMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
14  : BuiltinMessageParser<geometry_msgs::Twist>(topic_name, plot_data)
15  {
16  }
17 
18  void parseMessageImpl(const geometry_msgs::Twist& msg, double& timestamp) override
19  {
20  if( !_initialized )
21  {
22  _initialized = true;
23  _data.push_back(&getSeries(_topic_name + "/linear/x"));
24  _data.push_back(&getSeries(_topic_name + "/linear/y"));
25  _data.push_back(&getSeries(_topic_name + "/linear/z"));
26 
27  _data.push_back(&getSeries(_topic_name + "/angular/x"));
28  _data.push_back(&getSeries(_topic_name + "/angular/y"));
29  _data.push_back(&getSeries(_topic_name + "/angular/z"));
30  }
31  _data[0]->pushBack({ timestamp, msg.linear.x });
32  _data[1]->pushBack({ timestamp, msg.linear.y });
33  _data[2]->pushBack({ timestamp, msg.linear.z });
34 
35  _data[3]->pushBack({ timestamp, msg.angular.x });
36  _data[4]->pushBack({ timestamp, msg.angular.y });
37  _data[5]->pushBack({ timestamp, msg.angular.z });
38  }
39 
40 private:
41  std::vector<PJ::PlotData*> _data;
42  bool _initialized = false;
43 };
44 
45 class TwistStampedMsgParser : public BuiltinMessageParser<geometry_msgs::TwistStamped>
46 {
47 public:
48  TwistStampedMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
49  : BuiltinMessageParser<geometry_msgs::TwistStamped>(topic_name, plot_data)
50  , _header_parser(topic_name + "/header", plot_data)
51  , _twist_parser(topic_name + "/twist", plot_data)
52  {
53  }
54 
55  void parseMessageImpl(const geometry_msgs::TwistStamped& msg, double& timestamp) override
56  {
57  _header_parser.parse(msg.header, timestamp, _config.use_header_stamp);
58  _twist_parser.parseMessageImpl(msg.twist, timestamp);
59  }
60 
61 private:
64 };
65 
66 class TwistCovarianceMsgParser : public BuiltinMessageParser<geometry_msgs::TwistWithCovariance>
67 {
68 public:
69  TwistCovarianceMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
70  : BuiltinMessageParser<geometry_msgs::TwistWithCovariance>(topic_name, plot_data)
71  , _twist_parser(topic_name + "/twist", plot_data)
72  , _covariance(topic_name + "/covariance", plot_data)
73  {
74  }
75 
76  void parseMessageImpl(const geometry_msgs::TwistWithCovariance& msg, double& timestamp) override
77  {
78  _twist_parser.parseMessageImpl(msg.twist, timestamp);
79  _covariance.parse(msg.covariance, timestamp);
80  }
81 
82 private:
85 };
TwistCovarianceMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
TwistStampedMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
CovarianceParser< 6 > _covariance
PJ::PlotData & getSeries(const std::string &key)
std::vector< PJ::PlotData * > _data
void parseMessageImpl(const geometry_msgs::TwistWithCovariance &msg, double &timestamp) override
std::string _topic_name
void parseMessageImpl(const geometry_msgs::Twist &msg, double &timestamp) override
void parseMessageImpl(const geometry_msgs::TwistStamped &msg, double &timestamp) override
TwistMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Fri Jun 23 2023 02:28:04