ros2_parsers/imu_msg.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <sensor_msgs/msg/imu.hpp>
4 #include "fmt/format.h"
5 #include "ros2_parser.h"
6 #include "covariance_util.h"
7 #include "quaternion_msg.h"
8 #include "header_msg.h"
9 
10 class ImuMsgParser : public BuiltinMessageParser<sensor_msgs::msg::Imu>
11 {
12  public:
13  ImuMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data)
14  : BuiltinMessageParser<sensor_msgs::msg::Imu>(topic_name, plot_data)
15  , _header_parser(topic_name + "/header", plot_data)
16  , _quat_parser(topic_name + "/orientation", plot_data)
17  , _orientation_covariance(topic_name + "/orientation_covariance", plot_data)
18  , _lin_acc_covariance(topic_name + "/linear_acceleration_covariance", plot_data)
19  , _ang_vel_covariance(topic_name + "/angular_velocity_covariance", plot_data)
20  {
21  }
22 
23  void parseMessageImpl(const sensor_msgs::msg::Imu& msg, double& timestamp) override
24  {
25  if( !_initialized )
26  {
27  _initialized = true;
28  _data.push_back(&getSeries(_topic_name + "/angular_velocity/x"));
29  _data.push_back(&getSeries(_topic_name + "/angular_velocity/y"));
30  _data.push_back(&getSeries(_topic_name + "/angular_velocity/z"));
31 
32  _data.push_back(&getSeries(_topic_name + "/linear_acceleration/x"));
33  _data.push_back(&getSeries(_topic_name + "/linear_acceleration/y"));
34  _data.push_back(&getSeries(_topic_name + "/linear_acceleration/z"));
35  }
36 
37  _header_parser.parse(msg.header, timestamp, _config.use_header_stamp);
38 
39  _data[0]->pushBack({ timestamp, msg.angular_velocity.x });
40  _data[1]->pushBack({ timestamp, msg.angular_velocity.y });
41  _data[2]->pushBack({ timestamp, msg.angular_velocity.z });
42 
43  _data[3]->pushBack({ timestamp, msg.linear_acceleration.x });
44  _data[4]->pushBack({ timestamp, msg.linear_acceleration.y });
45  _data[5]->pushBack({ timestamp, msg.linear_acceleration.z });
46 
47  _quat_parser.parseMessageImpl(msg.orientation, timestamp);
48 
49  _orientation_covariance.parse(msg.orientation_covariance, timestamp);
50  _lin_acc_covariance.parse(msg.linear_acceleration_covariance, timestamp);
51  _ang_vel_covariance.parse(msg.angular_velocity_covariance, timestamp);
52  }
53 
54  private:
60  std::vector<PJ::PlotData*> _data;
61 
62  bool _initialized = false;
63 };
void parseMessageImpl(const geometry_msgs::Quaternion &msg, double &timestamp) override
PJ::PlotData & getSeries(const std::string &key)
void parse(const boost::array< double, N *N > &covariance, double &timestamp)
CovarianceParser< 3 > _orientation_covariance
CovarianceParser< 3 > _ang_vel_covariance
HeaderMsgParser _header_parser
void parse(const std_msgs::Header &msg, double &timestamp, bool use_header_stamp)
QuaternionMsgParser _quat_parser
std::vector< PJ::PlotData * > _data
void parseMessageImpl(const sensor_msgs::msg::Imu &msg, double &timestamp) override
std::string _topic_name
ImuMsgParser(const std::string &topic_name, PJ::PlotDataMapRef &plot_data)
msg
CovarianceParser< 3 > _lin_acc_covariance


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