Go to the documentation of this file. 1 #ifndef DATASTREAM_ROS2_TOPIC_H
2 #define DATASTREAM_ROS2_TOPIC_H
11 #include "rclcpp/generic_subscription.hpp"
16 Q_PLUGIN_METADATA(IID
"facontidavide.PlotJuggler3.ROS2DataStreamer")
22 bool start(QStringList* selected_datasources)
override;
30 const char*
name()
const override
32 return "ROS2 Topic Subscriber";
35 bool xmlSaveState(QDomDocument& doc, QDomElement& parent_element)
const override;
37 bool xmlLoadState(
const QDomElement& parent_element)
override;
42 void messageCallback(
const std::string& topic_name, std::shared_ptr<rclcpp::SerializedMessage> msg);
46 std::unique_ptr<rclcpp::executors::MultiThreadedExecutor>
_executor;
47 std::shared_ptr<rclcpp::Node>
_node;
66 std::unordered_map<std::string, rclcpp::GenericSubscription::SharedPtr>
_subscriptions;
68 void subscribeToTopic(
const std::string& topic_name,
const std::string& topic_type);
std::shared_ptr< rclcpp::Context > _context
bool start(QStringList *selected_datasources) override
bool isRunning() const override
void messageCallback(const std::string &topic_name, std::shared_ptr< rclcpp::SerializedMessage > msg)
rcl_time_point_value_t _start_time
bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override
std::unordered_map< std::string, rclcpp::GenericSubscription::SharedPtr > _subscriptions
~DataStreamROS2() override
void loadDefaultSettings()
bool xmlLoadState(const QDomElement &parent_element) override
const char * name() const override
std::shared_ptr< rclcpp::Node > _node
const std::vector< QAction * > & availableActions() override
PJ::CompositeParser _parser
void saveDefaultSettings()
std::unique_ptr< rclcpp::executors::MultiThreadedExecutor > _executor
PJ::RosParserConfig _config
void subscribeToTopic(const std::string &topic_name, const std::string &topic_type)
plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Wed Feb 21 2024 03:22:55