moveit2
The MoveIt Motion Planning Framework for ROS 2.
current_state_monitor_middleware_handle.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Tyler Weaver */
36 
37 #pragma once
38 
39 #include <chrono>
40 #include <string>
41 
42 #include <rclcpp/rclcpp.hpp>
43 #include <sensor_msgs/msg/joint_state.hpp>
44 
46 
47 namespace planning_scene_monitor
48 {
53 {
54 public:
60  CurrentStateMonitorMiddlewareHandle(const rclcpp::Node::SharedPtr& node);
61 
67  rclcpp::Time now() const override;
68 
75  void createJointStateSubscription(const std::string& topic, JointStateUpdateCallback callback) override;
76 
82  void createStaticTfSubscription(std::function<void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override;
83 
89  void
90  createDynamicTfSubscription(std::function<void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> callback) override;
91 
95  void resetJointStateSubscription() override;
96 
102  std::string getJointStateTopicName() const override;
103 
111  bool sleepFor(const std::chrono::nanoseconds& nanoseconds) const override;
112 
118  bool ok() const override;
119 
125  std::string getStaticTfTopicName() const override;
126 
132  std::string getDynamicTfTopicName() const override;
133 
137  void resetTfSubscriptions() override;
138 
139 private:
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_;
144 };
145 
146 } // namespace planning_scene_monitor
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.
Dependency injection class for testing the CurrentStateMonitor.
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback