39 #include <std_msgs/msg/string.hpp>
40 #include <rclcpp/rclcpp.hpp>
63 const StringCallback& parent_callback = {},
bool default_continuous_value =
false,
64 double default_timeout = 10.0);
73 void stringCallback(
const std_msgs::msg::String::ConstSharedPtr& msg);
75 std::shared_ptr<rclcpp::Node>
node_;
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)
std::shared_ptr< rclcpp::Node > node_
bool waitForMessage(const rclcpp::Duration &timeout)
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr string_publisher_
StringCallback parent_callback_
void stringCallback(const std_msgs::msg::String::ConstSharedPtr &msg)
std::function< void(const std::string &)> StringCallback