ros2_parsers/pose_msg.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <geometry_msgs/msg/pose.hpp>
4 #include <geometry_msgs/msg/pose_stamped.hpp>
5 #include <geometry_msgs/msg/pose_with_covariance.hpp>
6 #include "covariance_util.h"
7 #include "quaternion_msg.h"
8 #include "ros2_parser.h"
9 #include "header_msg.h"
10 
11 class PoseMsgParser : public BuiltinMessageParser<geometry_msgs::msg::Pose>
12 {
13  public:
14  PoseMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
15  : BuiltinMessageParser<geometry_msgs::msg::Pose>(topic_name, plot_data)
16  , _quat_parser(topic_name + "/orientation", plot_data)
17  {
18  }
19 
20  void parseMessageImpl(const geometry_msgs::msg::Pose& msg, double& timestamp) override
21  {
22  if( !_initialized )
23  {
24  _initialized = true;
25  _data.push_back(&getSeries(_topic_name + "/position/x"));
26  _data.push_back(&getSeries(_topic_name + "/position/y"));
27  _data.push_back(&getSeries(_topic_name + "/position/z"));
28  }
29  _data[0]->pushBack({ timestamp, msg.position.x });
30  _data[1]->pushBack({ timestamp, msg.position.y });
31  _data[2]->pushBack({ timestamp, msg.position.z });
32 
33  _quat_parser.parseMessageImpl(msg.orientation, timestamp);
34  }
35 
36  private:
37  bool _initialized = false;
39  std::vector<PJ::PlotData*> _data;
40 };
41 
43  : public BuiltinMessageParser<geometry_msgs::msg::PoseStamped>
44 {
45  public:
46  PoseStampedMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
47  : BuiltinMessageParser<geometry_msgs::msg::PoseStamped>(topic_name, plot_data)
48  , _header_parser(topic_name + "/header", plot_data)
49  , _pose_parser(topic_name + "/pose", plot_data)
50  {
51  }
52 
53  void parseMessageImpl(const geometry_msgs::msg::PoseStamped& msg, double& timestamp) override
54  {
55  _header_parser.parse(msg.header, timestamp, _config.use_header_stamp);
56  _pose_parser.parseMessageImpl(msg.pose, timestamp);
57  }
58 
59  private:
60  HeaderMsgParser _header_parser;
61  PoseMsgParser _pose_parser;
62  std::vector<PJ::PlotData*> _data;
63 };
64 
66  : public BuiltinMessageParser<geometry_msgs::msg::PoseWithCovariance>
67 {
68  public:
69  PoseCovarianceMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
70  : BuiltinMessageParser<geometry_msgs::msg::PoseWithCovariance>(topic_name, plot_data)
71  , _pose_parser(topic_name + "/pose", plot_data)
72  , _covariance(topic_name + "/covariance", plot_data)
73  {
74  }
75 
76  void parseMessageImpl(const geometry_msgs::msg::PoseWithCovariance& msg, double& timestamp) override
77  {
78  _pose_parser.parseMessageImpl(msg.pose, timestamp);
79  _covariance.parse(msg.covariance, timestamp);
80  }
81 
82  private:
83  PoseMsgParser _pose_parser;
84  CovarianceParser<6> _covariance;
85 };
86 
void parseMessageImpl(const geometry_msgs::Quaternion &msg, double &timestamp) override
void parseMessageImpl(const geometry_msgs::msg::PoseWithCovariance &msg, double &timestamp) override
std::vector< PJ::PlotData * > _data
PJ::PlotData & getSeries(const std::string &key)
QuaternionMsgParser _quat_parser
void parseMessageImpl(const geometry_msgs::msg::Pose &msg, double &timestamp) override
PoseMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
PoseStampedMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
PoseCovarianceMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
void parseMessageImpl(const geometry_msgs::msg::PoseStamped &msg, double &timestamp) override
std::string _topic_name
msg


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