3 #include <geometry_msgs/msg/pose.hpp> 4 #include <geometry_msgs/msg/pose_stamped.hpp> 5 #include <geometry_msgs/msg/pose_with_covariance.hpp> 29 _data[0]->pushBack({ timestamp, msg.position.x });
30 _data[1]->pushBack({ timestamp, msg.position.y });
31 _data[2]->pushBack({ timestamp, msg.position.z });
39 std::vector<PJ::PlotData*>
_data;
48 , _header_parser(topic_name +
"/header", plot_data)
49 , _pose_parser(topic_name +
"/pose", plot_data)
53 void parseMessageImpl(
const geometry_msgs::msg::PoseStamped& msg,
double& timestamp)
override 56 _pose_parser.parseMessageImpl(msg.pose, timestamp);
62 std::vector<PJ::PlotData*>
_data;
71 , _pose_parser(topic_name +
"/pose", plot_data)
72 , _covariance(topic_name +
"/covariance", plot_data)
76 void parseMessageImpl(
const geometry_msgs::msg::PoseWithCovariance& msg,
double& timestamp)
override 78 _pose_parser.parseMessageImpl(msg.pose, timestamp);
79 _covariance.parse(msg.covariance, timestamp);
void parseMessageImpl(const geometry_msgs::Quaternion &msg, double ×tamp) override
void parseMessageImpl(const geometry_msgs::msg::PoseWithCovariance &msg, double ×tamp) 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 ×tamp) 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 ×tamp) override