moveit2
The MoveIt Motion Planning Framework for ROS 2.
synchronized_string_parameter.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Robotics
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 Robotics 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: David V. Lu!! */
36 
37 #pragma once
38 
39 #include <std_msgs/msg/string.hpp>
40 #include <rclcpp/rclcpp.hpp>
41 
42 namespace rdf_loader
43 {
44 using StringCallback = std::function<void(const std::string&)>;
45 
60 {
61 public:
62  std::string loadInitialValue(const std::shared_ptr<rclcpp::Node>& node, const std::string& name,
63  const StringCallback& parent_callback = {}, bool default_continuous_value = false,
64  double default_timeout = 10.0);
65 
66 protected:
67  bool getMainParameter();
68 
69  bool shouldPublish();
70 
71  bool waitForMessage(const rclcpp::Duration& timeout);
72 
73  void stringCallback(const std_msgs::msg::String::ConstSharedPtr& msg);
74 
75  std::shared_ptr<rclcpp::Node> node_;
76  std::string name_;
78 
79  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr string_subscriber_;
80  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr string_publisher_;
81 
82  std::string content_;
83 };
84 } // namespace rdf_loader
SynchronizedStringParameter is a way to load a string from the ROS environment.
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr string_subscriber_
std::string loadInitialValue(const std::shared_ptr< rclcpp::Node > &node, const std::string &name, const StringCallback &parent_callback={}, bool default_continuous_value=false, double default_timeout=10.0)
bool waitForMessage(const rclcpp::Duration &timeout)
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr string_publisher_
void stringCallback(const std_msgs::msg::String::ConstSharedPtr &msg)
std::function< void(const std::string &)> StringCallback
name
Definition: setup.py:7