diff --git a/3rdparty/data_tamer_parser/data_tamer_parser.hpp b/3rdparty/data_tamer_parser/data_tamer_parser.hpp index 64f1db895..c2bd77090 100644 --- a/3rdparty/data_tamer_parser/data_tamer_parser.hpp +++ b/3rdparty/data_tamer_parser/data_tamer_parser.hpp @@ -425,7 +425,7 @@ inline bool ParseSnapshot(const Schema& schema, SnapshotView snapshot, const auto& field = schema.fields[i]; if (GetBit(snapshot.active_mask, i)) { - ParseSnapshotRecursive(field, schema.custom_types, buffer, callback_number, ""); + ParseSnapshotRecursive(field, schema.custom_types, buffer, callback_number, {}); } } return true; diff --git a/plotjuggler_base/include/PlotJuggler/messageparser_base.h b/plotjuggler_base/include/PlotJuggler/messageparser_base.h index c506e13ba..f57d00e5d 100644 --- a/plotjuggler_base/include/PlotJuggler/messageparser_base.h +++ b/plotjuggler_base/include/PlotJuggler/messageparser_base.h @@ -8,12 +8,7 @@ #include #include -#include -#include -#include -#include #include -#include #include "PlotJuggler/plotdata.h" #include "PlotJuggler/pj_plugin.h" @@ -109,6 +104,16 @@ class MessageParser return _clamp_large_arrays; } + virtual bool useEmbeddedTimestamp() const + { + return _use_embedded_timestamp; + } + + virtual void enableEmbeddedTimestamp(bool enable) + { + _use_embedded_timestamp = enable; + } + protected: PlotDataMapRef& _plot_data; std::string _topic_name; @@ -125,6 +130,7 @@ class MessageParser private: bool _clamp_large_arrays = false; unsigned _max_array_size = 10000; + bool _use_embedded_timestamp = false; }; using MessageParserPtr = std::shared_ptr; diff --git a/plotjuggler_base/include/PlotJuggler/special_messages.h b/plotjuggler_base/include/PlotJuggler/special_messages.h index 3c3e8037d..8fdf5e8d0 100644 --- a/plotjuggler_base/include/PlotJuggler/special_messages.h +++ b/plotjuggler_base/include/PlotJuggler/special_messages.h @@ -4,6 +4,7 @@ //These messages are exact equivalents of ROS messages +#include #include #include #include @@ -58,6 +59,15 @@ struct Vector3 static const char* id() { return "geometry_msgs/Vector3"; } }; +struct Point +{ + double x; + double y; + double z; + + static const char* id() { return "geometry_msgs/Point"; } +}; + struct Quaternion { double x; @@ -79,7 +89,7 @@ RPY QuaternionToRPY(Quaternion q); struct Transform { - Vector3 translation; + Point translation; Quaternion rotation; static const char* id() { return "geometry_msgs/Transform"; } @@ -87,11 +97,51 @@ struct Transform struct TransformStamped { - Header header; - std::string child_frame_id; - Transform transform; + Header header; + std::string child_frame_id; + Transform transform; + + static const char* id() { return "geometry_msgs/TransformStamped"; } +}; + +struct Pose +{ + Vector3 position; + Quaternion orientation; + + static const char* id() { return "geometry_msgs/Pose"; } +}; + +struct PoseStamped +{ + Header header; + Pose pose; + + static const char* id() { return "geometry_msgs/PoseStamped"; } +}; + +struct PoseWithCovariance +{ + Pose pose; + std::array covariance; - static const char* id() { return "geometry_msgs/TransformStamped"; } + static const char* id() { return "geometry_msgs/PoseWithCovariance"; } +}; + +struct Twist +{ + Vector3 linear; + Vector3 angular; + + static const char* id() { return "geometry_msgs/Twist"; } +}; + +struct TwistWithCovariance +{ + Twist twist; + std::array covariance; + + static const char* id() { return "geometry_msgs/TwistWithCovariance"; } }; struct TFMessage @@ -102,6 +152,30 @@ struct TFMessage }; //-------------------- +struct Imu +{ + Header header; + Quaternion orientation; + std::array orientation_covariance; + Vector3 angular_velocity; + std::array angular_velocity_covariance; + Vector3 linear_acceleration; + std::array linear_acceleration_covariance; + + static const char* id() { return "sensor_msgs/Imu"; } +}; +//-------------------- +struct Odometry +{ + Header header; + PoseWithCovariance pose; + TwistWithCovariance twist; + + static const char* id() { return "nav_msgs/Odometry"; } +}; + +//-------------------- + struct JointState { Header header; diff --git a/plotjuggler_plugins/DataLoadMCAP/dataload_mcap.cpp b/plotjuggler_plugins/DataLoadMCAP/dataload_mcap.cpp index 15a9cb19b..0fa508f07 100644 --- a/plotjuggler_plugins/DataLoadMCAP/dataload_mcap.cpp +++ b/plotjuggler_plugins/DataLoadMCAP/dataload_mcap.cpp @@ -14,6 +14,7 @@ #include "mcap/reader.hpp" #include "dialog_mcap.h" +#include #include DataLoadMCAP::DataLoadMCAP() @@ -80,6 +81,10 @@ bool DataLoadMCAP::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_dat std::set notified_encoding_problem; + + QElapsedTimer timer; + timer.start(); + for (const auto& [channel_id, channel_ptr] : reader.channels()) { channels.insert( {channel_id, channel_ptr} ); @@ -193,15 +198,6 @@ bool DataLoadMCAP::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_dat MessageRef msg(msg_view.message.data, msg_view.message.dataSize); parser->parseMessage(msg, timestamp_sec); - // data tamer schema - if( channels_containing_datatamer_schema.count(msg_view.channel->id) != 0) - { - - - } - - // regular message - if (msg_count++ % 1000 == 0) { QApplication::processEvents(); @@ -213,6 +209,7 @@ bool DataLoadMCAP::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_dat } reader.close(); + qDebug() << "Loaded file in " << timer.elapsed() << "milliseconds"; return true; } diff --git a/plotjuggler_plugins/DataLoadMCAP/dialog_mcap.cpp b/plotjuggler_plugins/DataLoadMCAP/dialog_mcap.cpp index 9224cc43b..ed1bb5bc7 100644 --- a/plotjuggler_plugins/DataLoadMCAP/dialog_mcap.cpp +++ b/plotjuggler_plugins/DataLoadMCAP/dialog_mcap.cpp @@ -4,6 +4,7 @@ #include #include #include +#include const QString DialogMCAP::prefix = "DialogLoadMCAP::"; diff --git a/plotjuggler_plugins/ParserROS/ros_parser.cpp b/plotjuggler_plugins/ParserROS/ros_parser.cpp index b123f9baf..6715a0c94 100644 --- a/plotjuggler_plugins/ParserROS/ros_parser.cpp +++ b/plotjuggler_plugins/ParserROS/ros_parser.cpp @@ -1,6 +1,6 @@ #include "ros_parser.h" #include "data_tamer_parser/data_tamer_parser.hpp" -#include "PlotJuggler/fmt/format.h" +#include "PlotJuggler/fmt/core.h" using namespace PJ; using namespace RosMsgParser; @@ -47,23 +47,38 @@ ParserROS::ParserROS(const std::string& topic_name, { _customized_parser = std::bind(&ParserROS::parseDataTamerSnapshotMsg, this, _1, _2); } - - //---------- detect quaternion in schema -------- - auto hasQuaternion = [this](const auto& node) { - if(node->value()->type() == quaternion_type) - { - _contains_quaternion = true; - } - }; - const auto& tree = _parser.getSchema()->field_tree; - tree.visit(hasQuaternion, tree.croot()); + else if( Msg::Imu::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parseImu, this, _1, _2); + } + else if( Msg::Pose::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parsePose, this, _1, _2); + } + else if( Msg::PoseStamped::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parsePoseStamped, this, _1, _2); + } + else if( Msg::Odometry::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parseOdometry, this, _1, _2); + } + else if( Msg::Transform::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parseTransform, this, _1, _2); + } + else if( Msg::TransformStamped::id() == type_name) + { + _customized_parser = std::bind(&ParserROS::parseTransformStamped, this, _1, _2); + } } bool ParserROS::parseMessage(const PJ::MessageRef serialized_msg, double ×tamp) { if( _customized_parser ) { - _customized_parser(serialized_msg, timestamp); + _deserializer->init( Span(serialized_msg.data(), serialized_msg.size()) ); + _customized_parser(_topic_name, timestamp); return true; } @@ -84,11 +99,6 @@ bool ParserROS::parseMessage(const PJ::MessageRef serialized_msg, double ×t PlotData& data = getSeries(series_name); data.pushBack( {timestamp, value.convert() } ); } - - if( _contains_quaternion ) - { - appendRollPitchYaw(timestamp); - } return true; } @@ -97,72 +107,159 @@ void ParserROS::setLargeArraysPolicy(bool clamp, unsigned max_size) auto policy = clamp ? RosMsgParser::Parser::KEEP_LARGE_ARRAYS : RosMsgParser::Parser::DISCARD_LARGE_ARRAYS; - _parser.setMaxArrayPolicy( policy, max_size ); + _parser.setMaxArrayPolicy( policy, max_size ); MessageParser::setLargeArraysPolicy(clamp, max_size); } -void ParserROS::appendRollPitchYaw(double stamp) +//------------------------------------------------------------------------ + +Msg::Header ParserROS::parseHeader(const std::string &prefix, double& timestamp) { + Msg::Header header; + const bool is_ros1 = dynamic_cast(_deserializer.get()) != nullptr; + // only ROS1 as the files header.seq + if( is_ros1 ) + { + header.seq = _deserializer->deserializeUInt32(); + } - for(size_t i=0; i< _flat_msg.value.size(); i++ ) - { - const auto& [key, val] = _flat_msg.value[i]; + header.stamp.sec = _deserializer->deserializeUInt32(); + header.stamp.nanosec = _deserializer->deserializeUInt32(); - if( key.fields.size() < 2 || (i+3) >= _flat_msg.value.size() ) - { - continue; + const double ts = double(header.stamp.sec) + 1e-9*double(header.stamp.nanosec); + if(useEmbeddedTimestamp()) { + timestamp = ts; } - size_t last = key.fields.size() - 1; - if( key.fields[last-1]->type() == quaternion_type && - key.fields[last]->type().typeID() == RosMsgParser::FLOAT64 && - key.fields[last]->name() == "x") + _deserializer->deserializeString(header.frame_id); + + getSeries(prefix + "/header/stamp").pushBack( {timestamp, ts} ); + if( is_ros1 ) { - Msg::Quaternion quat; + getSeries(prefix + "/header/seq").pushBack( {timestamp, double(header.seq)} ); + } + getStringSeries(prefix + "/header/frame_id").pushBack( {timestamp, header.frame_id} ); - quat.x = val.convert(); - quat.y = _flat_msg.value[i+1].second.convert(); - quat.z = _flat_msg.value[i+2].second.convert(); - quat.w = _flat_msg.value[i+3].second.convert(); + return header; +} - std::string prefix = key.toStdString(); - prefix.pop_back(); +void ParserROS::parseVector3(const std::string &prefix, double& timestamp) +{ + auto x = _deserializer->deserialize(FLOAT64).convert(); + auto y = _deserializer->deserialize(FLOAT64).convert(); + auto z = _deserializer->deserialize(FLOAT64).convert(); + getSeries(prefix + "/x").pushBack( {timestamp, x} ); + getSeries(prefix + "/y").pushBack( {timestamp, y} ); + getSeries(prefix + "/z").pushBack( {timestamp, z} ); +} - auto rpy = Msg::QuaternionToRPY( quat ); +void ParserROS::parsePoint(const std::string &prefix, double& timestamp) +{ + auto x = _deserializer->deserialize(FLOAT64).convert(); + auto y = _deserializer->deserialize(FLOAT64).convert(); + auto z = _deserializer->deserialize(FLOAT64).convert(); + getSeries(prefix + "/x").pushBack( {timestamp, x} ); + getSeries(prefix + "/y").pushBack( {timestamp, y} ); + getSeries(prefix + "/z").pushBack( {timestamp, z} ); +} - getSeries(prefix + "roll_deg").pushBack( {stamp, RAD_TO_DEG * rpy.roll } ); - getSeries(prefix + "pitch_deg").pushBack( {stamp, RAD_TO_DEG * rpy.pitch } ); - getSeries(prefix + "yaw_deg").pushBack( {stamp, RAD_TO_DEG * rpy.yaw } ); +void ParserROS::parseQuaternion(const std::string &prefix, double& timestamp) +{ + PJ::Msg::Quaternion quat; + quat.x = _deserializer->deserialize(FLOAT64).convert(); + quat.y = _deserializer->deserialize(FLOAT64).convert(); + quat.z = _deserializer->deserialize(FLOAT64).convert(); + quat.w = _deserializer->deserialize(FLOAT64).convert(); + getSeries(prefix + "/x").pushBack( {timestamp, quat.x} ); + getSeries(prefix + "/y").pushBack( {timestamp, quat.y} ); + getSeries(prefix + "/z").pushBack( {timestamp, quat.z} ); + getSeries(prefix + "/z").pushBack( {timestamp, quat.w} ); + + auto rpy = Msg::QuaternionToRPY( quat ); + getSeries(prefix + "/roll").pushBack( {timestamp, rpy.roll} ); + getSeries(prefix + "/pitch").pushBack( {timestamp, rpy.pitch} ); + getSeries(prefix + "/yaw").pushBack( {timestamp, rpy.yaw} ); +} - break; - } - } + +void ParserROS::parseTwist(const std::string &prefix, double& timestamp) +{ + parseVector3(prefix + "/linear", timestamp); + parseVector3(prefix + "/angular", timestamp); } -void ParserROS::parseHeader(Msg::Header &header) + +void ParserROS::parseTwistWithCovariance(const std::string &prefix, double& timestamp) { - // only ROS1 as the files header.seq - if( dynamic_cast(_deserializer.get()) ) - { - header.seq = _deserializer->deserializeUInt32(); - } + parseTwist(prefix + "/twist", timestamp); + parseCovariance<6>(prefix + "/covariance", timestamp); +} + +void ParserROS::parseTransform(const std::string &prefix, double& timestamp) +{ + parsePoint(prefix + "/translation", timestamp); + parseQuaternion(prefix + "/rotation", timestamp); +} + +void ParserROS::parseTransformStamped(const std::string &prefix, double& timestamp) +{ + parseHeader(prefix + "/header", timestamp); - header.stamp.sec = _deserializer->deserializeUInt32(); - header.stamp.nanosec = _deserializer->deserializeUInt32(); - _deserializer->deserializeString(header.frame_id); + std::string child_frame_id; + _deserializer->deserializeString(child_frame_id); + getStringSeries(prefix + "/child_frame_id").pushBack( {timestamp, child_frame_id} ); + + parseTransform(prefix + "/transform", timestamp); } -void ParserROS::parseDiagnosticMsg(const PJ::MessageRef msg_buffer, double ×tamp) +void ParserROS::parsePose(const std::string &prefix, double ×tamp) { - using namespace RosMsgParser; + parseVector3(prefix + "/position", timestamp); + parseQuaternion(prefix + "/orientation", timestamp); +} + +void ParserROS::parsePoseStamped(const std::string &prefix, double ×tamp) +{ + parseHeader(prefix + "/header", timestamp); + parsePose(prefix + "/pose", timestamp); +} + +void ParserROS::parsePoseWithCovariance(const std::string &prefix, double ×tamp) +{ + parsePose(prefix + "/pose", timestamp); + parseCovariance<6>(prefix + "/covariance", timestamp); +} + +void ParserROS::parseImu(const std::string &prefix, double ×tamp) +{ + parseHeader(prefix + "/header", timestamp); + + parseQuaternion(prefix + "/orientation", timestamp); + parseCovariance<3>(prefix + "/orientation_covariance", timestamp); + parseVector3(prefix + "/angular_velocity", timestamp); + parseCovariance<3>(prefix + "/angular_velocity_covariance", timestamp); + + parseVector3(prefix + "/linear_acceleration", timestamp); + parseCovariance<3>(prefix + "/linear_acceleration_covariance", timestamp); +} + +void ParserROS::parseOdometry(const std::string &prefix, double ×tamp) +{ + parseHeader(prefix + "/header", timestamp); + parsePoseWithCovariance(prefix + "/pose", timestamp); + parseTwistWithCovariance(prefix + "/twist", timestamp); +} + +void ParserROS::parseDiagnosticMsg(const std::string &prefix, double ×tamp) +{ thread_local Msg::DiagnosticArray msg; - _deserializer->init( Span(msg_buffer.data(), msg_buffer.size()) ); - parseHeader(msg.header); + parseHeader(prefix + "/header", timestamp); size_t status_count = _deserializer->deserializeUInt32(); msg.status.resize( status_count ); + for(size_t st = 0; st < status_count; st++) { auto& status = msg.status[st]; @@ -185,10 +282,6 @@ void ParserROS::parseDiagnosticMsg(const PJ::MessageRef msg_buffer, double &time } //------ Now create the series -------- - double ts = timestamp; - getSeries(fmt::format("{}/header/seq", _topic)).pushBack( {ts, double(msg.header.seq)} ); - getSeries(fmt::format("{}/header/stamp", _topic)).pushBack( {ts, msg.header.stamp.toSec()} ); - getStringSeries(fmt::format("{}/header/frame_id", _topic)).pushBack( {ts, msg.header.frame_id} ); std::string series_name; @@ -199,11 +292,11 @@ void ParserROS::parseDiagnosticMsg(const PJ::MessageRef msg_buffer, double &time if (status.hardware_id.empty()) { series_name = fmt::format("{}/{}/{}", - _topic, status.name, kv.first); + prefix, status.name, kv.first); } else { series_name = fmt::format("{}/{}/{}/{}", - _topic, status.hardware_id, status.name, kv.first); + prefix, status.hardware_id, status.name, kv.first); } bool ok; @@ -220,17 +313,16 @@ void ParserROS::parseDiagnosticMsg(const PJ::MessageRef msg_buffer, double &time } } -void ParserROS::parseJointStateMsg(const MessageRef msg_buffer, double ×tamp) +void ParserROS::parseJointStateMsg(const std::string &prefix, double ×tamp) { thread_local Msg::JointState msg; - _deserializer->init( Span(msg_buffer.data(), msg_buffer.size()) ); msg.name.clear(); msg.position.clear(); msg.velocity.clear(); msg.effort.clear(); - parseHeader(msg.header); + parseHeader(prefix, timestamp); size_t name_size = _deserializer->deserializeUInt32(); if( name_size > 0 ) @@ -291,65 +383,35 @@ void ParserROS::parseJointStateMsg(const MessageRef msg_buffer, double ×tam } } -void ParserROS::parseTF2Msg(const MessageRef msg_buffer, double &stamp) +void ParserROS::parseTF2Msg(const std::string &prefix, double ×tamp) { - thread_local Msg::TFMessage msg; - _deserializer->init( Span(msg_buffer.data(), msg_buffer.size()) ); - - size_t transform_size = _deserializer->deserializeUInt32(); + const size_t transform_size = _deserializer->deserializeUInt32(); if( transform_size == 0) { return; } - msg.transforms.resize(transform_size); - auto getDouble = [this]() { - return _deserializer->deserialize(FLOAT64).convert(); - }; - - for(auto& trans: msg.transforms) + for(size_t i=0; ideserializeString(trans.child_frame_id); + auto header = parseHeader(prefix, timestamp); + std::string child_frame_id; + _deserializer->deserializeString(child_frame_id); - std::string prefix; - if (trans.header.frame_id.empty()) + std::string new_prefix; + if (header.frame_id.empty()) { - prefix = fmt::format("{}/{}", - _topic_name, trans.child_frame_id); + new_prefix = fmt::format("{}/{}", prefix, child_frame_id); } else { - prefix = fmt::format("{}/{}/{}", - _topic_name, trans.header.frame_id, trans.child_frame_id); + new_prefix = fmt::format("{}/{}/{}", prefix, header.frame_id, child_frame_id); } - - getSeries(fmt::format("{}/translation/x", prefix)).pushBack( {stamp, getDouble()} ); - getSeries(fmt::format("{}/translation/y", prefix)).pushBack( {stamp, getDouble()} ); - getSeries(fmt::format("{}/translation/z", prefix)).pushBack( {stamp, getDouble()} ); - - Msg::Quaternion quat = { getDouble(), getDouble(), getDouble(), getDouble() }; - auto RPY = Msg::QuaternionToRPY(quat); - - getSeries(fmt::format("{}/rotation/x", prefix)).pushBack( {stamp, quat.x} ); - getSeries(fmt::format("{}/rotation/y", prefix)).pushBack( {stamp, quat.y} ); - getSeries(fmt::format("{}/rotation/z", prefix)).pushBack( {stamp, quat.z} ); - getSeries(fmt::format("{}/rotation/w", prefix)).pushBack( {stamp, quat.w} ); - - getSeries(fmt::format("{}/rotation/roll_deg", prefix)).pushBack( - {stamp, RPY.roll * RAD_TO_DEG} ); - getSeries(fmt::format("{}/rotation/pitch_deg", prefix)).pushBack( - {stamp, RPY.roll * RAD_TO_DEG} ); - getSeries(fmt::format("{}/rotation/yaw_deg", prefix)).pushBack( - {stamp, RPY.yaw * RAD_TO_DEG} ); + parseTransform(new_prefix, timestamp); } - } -void ParserROS::parseDataTamerSchemasMsg(const PJ::MessageRef msg_buffer, double ×tamp) +void ParserROS::parseDataTamerSchemasMsg(const std::string &prefix, double ×tamp) { - _deserializer->init( Span(msg_buffer.data(), msg_buffer.size()) ); - const size_t vector_size = _deserializer->deserializeUInt32(); for(size_t i=0; iinit( Span(msg_buffer.data(), msg_buffer.size()) ); - DataTamerParser::SnapshotView snapshot; snapshot.timestamp = _deserializer->deserialize(BuiltinType::UINT64).convert(); diff --git a/plotjuggler_plugins/ParserROS/ros_parser.h b/plotjuggler_plugins/ParserROS/ros_parser.h index 68bcf1429..7528c6dc2 100644 --- a/plotjuggler_plugins/ParserROS/ros_parser.h +++ b/plotjuggler_plugins/ParserROS/ros_parser.h @@ -1,6 +1,7 @@ #ifndef ROS_PARSER_H #define ROS_PARSER_H +#include "PlotJuggler/fmt/core.h" #include "PlotJuggler/messageparser_base.h" #include "PlotJuggler/special_messages.h" #include "rosx_introspection/ros_parser.hpp" @@ -9,7 +10,7 @@ class ParserROS : public PJ::MessageParser { public: ParserROS(const std::string& topic_name, - const std::string& type_name, + const std::string& type_name, const std::string& schema, RosMsgParser::Deserializer *deserializer, PJ::PlotDataMapRef& data); @@ -24,23 +25,59 @@ class ParserROS : public PJ::MessageParser RosMsgParser::FlatMessage _flat_msg; std::string _topic; - void appendRollPitchYaw(double timestamp); + PJ::Msg::Header parseHeader(const std::string& prefix, double& timestamp); - void parseHeader(PJ::Msg::Header& header); + template + void parseCovariance(const std::string& prefix, double& timestamp); - void parseDiagnosticMsg(const PJ::MessageRef msg_buffer, double ×tamp); + void parseVector3(const std::string& prefix, double& timestamp); + void parsePoint(const std::string& prefix, double& timestamp); + void parseQuaternion(const std::string& prefix, double& timestamp); - void parseJointStateMsg(const PJ::MessageRef msg_buffer, double ×tamp); + void parseTwist(const std::string& prefix, double& timestamp); + void parseTwistWithCovariance(const std::string& prefix, double& timestamp); - void parseTF2Msg(const PJ::MessageRef msg_buffer, double ×tamp); + void parseTransform(const std::string& prefix, double& timestamp); + void parseTransformStamped(const std::string& prefix, double& timestamp); - void parseDataTamerSchemasMsg(const PJ::MessageRef msg_buffer, double ×tamp); + void parsePose(const std::string& prefix, double& timestamp); + void parsePoseStamped(const std::string& prefix, double& timestamp); + void parsePoseWithCovariance(const std::string& prefix, double& timestamp); - void parseDataTamerSnapshotMsg(const PJ::MessageRef msg_buffer, double ×tamp); + void parseImu(const std::string& prefix, double& timestamp); + void parseOdometry(const std::string& prefix, double& timestamp); - std::function _customized_parser; + void parseDiagnosticMsg(const std::string& prefix, double& timestamp); + void parseJointStateMsg(const std::string& prefix, double& timestamp); + void parseTF2Msg(const std::string& prefix, double& timestamp); - bool _contains_quaternion = false; + void parseDataTamerSchemasMsg(const std::string& prefix, double& timestamp); + void parseDataTamerSnapshotMsg(const std::string& prefix, double& timestamp); + + std::function _customized_parser; + + bool _has_header = false; }; +template inline +void ParserROS::parseCovariance(const std::string &prefix, double ×tamp) +{ + std::array cov; + for(auto& val: cov) + { + _deserializer->deserialize(RosMsgParser::FLOAT64).convert(); + } + for(int i=0; i #include #include -#include #include "rosx_introspection/contrib/span.hpp" #include "rosx_introspection/contrib/SmallVector.h"