Go to the documentation of this file. 1 #ifndef DATALOAD_ROS2_H
2 #define DATALOAD_ROS2_H
8 #include <rosbag2_cpp/reader.hpp>
16 Q_PLUGIN_METADATA(IID
"facontidavide.PlotJuggler3.ROS2DataLoader")
27 virtual const char*
name()
const override
29 return "DataLoad ROS2 bags";
34 virtual bool xmlSaveState(QDomDocument& doc, QDomElement& parent_element)
const override;
36 virtual bool xmlLoadState(
const QDomElement& parent_element)
override;
52 #endif // DATALOAD_ROS2_H
virtual bool readDataFromFile(PJ::FileLoadInfo *fileload_info, PJ::PlotDataMapRef &destination) override
PJ::RosParserConfig _config
virtual bool xmlLoadState(const QDomElement &parent_element) override
std::vector< const char * > _extensions
virtual ~DataLoadROS2() override=default
void loadDefaultSettings()
std::vector< std::pair< QString, QString > > getAndRegisterAllTopics()
virtual bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override
virtual const char * name() const override
std::shared_ptr< rosbag2_cpp::Reader > _bag_reader
virtual const std::vector< const char * > & compatibleFileExtensions() const override
void saveDefaultSettings()
plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Wed Feb 21 2024 03:22:55