37#include <tf2_ros/qos.hpp>
39#include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
40#include <rclcpp/node.hpp>
41#include <rclcpp/qos.hpp>
42#include <rclcpp/version.h>
43#if RCLCPP_VERSION_GTE(20, 0, 0)
44#include <rclcpp/event_handler.hpp>
46#include <rclcpp/qos_event.hpp>
48#include <rclcpp/subscription.hpp>
49#include <rclcpp/time.hpp>
50#include <rclcpp/utilities.hpp>
53#include <tf2_ros/qos.hpp>
73 joint_state_subscription_ =
74 node_->create_subscription<sensor_msgs::msg::JointState>(topic, rclcpp::SystemDefaultsQoS(), callback);
79 joint_state_subscription_.reset();
84 if (joint_state_subscription_)
86 return joint_state_subscription_->get_topic_name();
96 return rclcpp::sleep_for(nanoseconds);
106 transform_subscriber_ =
107 node_->create_subscription<tf2_msgs::msg::TFMessage>(
"/tf", tf2_ros::DynamicListenerQoS(), callback);
112 static_transform_subscriber_ =
113 node_->create_subscription<tf2_msgs::msg::TFMessage>(
"/tf_static", tf2_ros::StaticListenerQoS(), callback);
118 return static_transform_subscriber_ ? static_transform_subscriber_->get_topic_name() :
"";
123 return transform_subscriber_ ? transform_subscriber_->get_topic_name() :
"";
128 transform_subscriber_.reset();
129 static_transform_subscriber_.reset();
bool ok() const override
Uses rclcpp::ok to check the context status.
std::string getJointStateTopicName() const override
Get the joint state topic name.
std::string getStaticTfTopicName() const override
Get the static transform topic name.
bool sleepFor(const std::chrono::nanoseconds &nanoseconds) const override
Uses rclcpp::sleep_for to sleep.
void createDynamicTfSubscription(std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override
Creates a dynamic transform message subscription.
void createStaticTfSubscription(std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override
Creates a static transform message subscription.
void resetTfSubscriptions() override
Reset the static & dynamic transform subscriptions.
void resetJointStateSubscription() override
Reset the joint state subscription.
CurrentStateMonitorMiddlewareHandle(const rclcpp::Node::SharedPtr &node)
Constructor.
void createJointStateSubscription(const std::string &topic, JointStateUpdateCallback callback) override
Creates a joint state subscription.
std::string getDynamicTfTopicName() const override
Get the dynamic transform topic name.
rclcpp::Time now() const override
Get the current time.
std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> TfCallback
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback