42 #include <rclcpp/rclcpp.hpp> 
   43 #include <sensor_msgs/msg/joint_state.hpp> 
   67   rclcpp::Time 
now() 
const override;
 
  111   bool sleepFor(
const std::chrono::nanoseconds& nanoseconds) 
const override;
 
  118   bool ok() 
const override;
 
  140   rclcpp::Node::SharedPtr node_;
 
  141   rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_subscription_;
 
  142   rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr transform_subscriber_;
 
  143   rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr static_transform_subscriber_;
 
This class contains the ros interfaces for CurrentStateMontior.
 
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.
 
Dependency injection class for testing the CurrentStateMonitor.
 
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback