moveit2
The MoveIt Motion Planning Framework for ROS 2.
current_state_monitor_middleware_handle.cpp
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 #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/qos_event.hpp>
43 #include <rclcpp/subscription.hpp>
44 #include <rclcpp/time.hpp>
45 #include <rclcpp/utilities.hpp>
46 #include <chrono>
47 #include <string>
48 #include <tf2_ros/qos.hpp>
49 
51 
52 namespace planning_scene_monitor
53 {
54 
56  : node_(node)
57 {
58 }
59 
61 {
62  return node_->now();
63 }
64 
66  JointStateUpdateCallback callback)
67 {
68  joint_state_subscription_ =
69  node_->create_subscription<sensor_msgs::msg::JointState>(topic, rclcpp::SystemDefaultsQoS(), callback);
70 }
71 
73 {
74  joint_state_subscription_.reset();
75 }
76 
78 {
79  if (joint_state_subscription_)
80  {
81  return joint_state_subscription_->get_topic_name();
82  }
83  else
84  {
85  return "";
86  }
87 }
88 
89 bool CurrentStateMonitorMiddlewareHandle::sleepFor(const std::chrono::nanoseconds& nanoseconds) const
90 {
91  return rclcpp::sleep_for(nanoseconds);
92 }
93 
95 {
96  return rclcpp::ok();
97 }
98 
100 {
101  transform_subscriber_ =
102  node_->create_subscription<tf2_msgs::msg::TFMessage>("/tf", tf2_ros::DynamicListenerQoS(), callback);
103 }
104 
106 {
107  static_transform_subscriber_ =
108  node_->create_subscription<tf2_msgs::msg::TFMessage>("/tf_static", tf2_ros::StaticListenerQoS(), callback);
109 }
110 
112 {
113  return static_transform_subscriber_ ? static_transform_subscriber_->get_topic_name() : "";
114 }
115 
117 {
118  return transform_subscriber_ ? transform_subscriber_->get_topic_name() : "";
119 }
120 
122 {
123  transform_subscriber_.reset();
124  static_transform_subscriber_.reset();
125 }
126 
127 } // namespace planning_scene_monitor
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.
std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> TfCallback
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback