3 #include <sensor_msgs/JointState.h> 20 for (
int i = 0;
i < msg.name.size();
i++)
22 const std::string prefix =
_topic_name +
"/" + msg.name[
i];
24 if (msg.name.size() == msg.position.size())
26 auto& series =
getSeries(prefix +
"/position");
27 series.pushBack({ timestamp, msg.position[
i] });
30 if (msg.name.size() == msg.velocity.size())
32 auto& series =
getSeries(prefix +
"/velocity");
33 series.pushBack({ timestamp, msg.velocity[
i] });
36 if (msg.name.size() == msg.effort.size())
38 auto& series =
getSeries(prefix +
"/effort");
39 series.pushBack({ timestamp, msg.effort[
i] });
PJ::PlotData & getSeries(const std::string &key)
HeaderMsgParser _header_parser
JointStateMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
void parseMessageImpl(const sensor_msgs::JointState &msg, double ×tamp) override