3 #include <geometry_msgs/Twist.h> 4 #include <geometry_msgs/TwistStamped.h> 5 #include <geometry_msgs/TwistWithCovariance.h> 31 _data[0]->pushBack({ timestamp, msg.linear.x });
32 _data[1]->pushBack({ timestamp, msg.linear.y });
33 _data[2]->pushBack({ timestamp, msg.linear.z });
35 _data[3]->pushBack({ timestamp, msg.angular.x });
36 _data[4]->pushBack({ timestamp, msg.angular.y });
37 _data[5]->pushBack({ timestamp, msg.angular.z });
41 std::vector<PJ::PlotData*>
_data;
50 , _header_parser(topic_name +
"/header", plot_data)
51 , _twist_parser(topic_name +
"/twist", plot_data)
55 void parseMessageImpl(
const geometry_msgs::TwistStamped& msg,
double& timestamp)
override 58 _twist_parser.parseMessageImpl(msg.twist, timestamp);
71 , _twist_parser(topic_name +
"/twist", plot_data)
72 , _covariance(topic_name +
"/covariance", plot_data)
76 void parseMessageImpl(
const geometry_msgs::TwistWithCovariance& msg,
double& timestamp)
override 78 _twist_parser.parseMessageImpl(msg.twist, timestamp);
79 _covariance.parse(msg.covariance, timestamp);
TwistCovarianceMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
TwistStampedMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
CovarianceParser< 6 > _covariance
TwistMsgParser _twist_parser
PJ::PlotData & getSeries(const std::string &key)
std::vector< PJ::PlotData * > _data
void parseMessageImpl(const geometry_msgs::TwistWithCovariance &msg, double ×tamp) override
TwistMsgParser _twist_parser
void parseMessageImpl(const geometry_msgs::Twist &msg, double ×tamp) override
void parseMessageImpl(const geometry_msgs::TwistStamped &msg, double ×tamp) override
HeaderMsgParser _header_parser
TwistMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)