moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
SynchronizedStringParameter is a way to load a string from the ROS environment. More...
#include <synchronized_string_parameter.h>
Public Member Functions | |
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) |
Protected Member Functions | |
bool | getMainParameter () |
bool | shouldPublish () |
bool | waitForMessage (const rclcpp::Duration &timeout) |
void | stringCallback (const std_msgs::msg::String::ConstSharedPtr &msg) |
Protected Attributes | |
std::shared_ptr< rclcpp::Node > | node_ |
std::string | name_ |
StringCallback | parent_callback_ |
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr | string_subscriber_ |
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr | string_publisher_ |
std::string | content_ |
SynchronizedStringParameter is a way to load a string from the ROS environment.
First it tries to load the string from a parameter. If that fails, it subscribes to a std_msgs::String topic of the same name to get the value.
If the parameter is loaded successfully, you can publish the value as a String msg if the publish_NAME param is true.
You can specify how long to wait for a subscribed message with NAME_timeout (double in seconds)
By default, the subscription will be killed after the first message is received. If the parameter NAME_continuous is true, then the parent_callback will be called on every subsequent message.
Definition at line 59 of file synchronized_string_parameter.h.
|
protected |
Definition at line 96 of file synchronized_string_parameter.cpp.
std::string rdf_loader::SynchronizedStringParameter::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 |
||
) |
Definition at line 41 of file synchronized_string_parameter.cpp.
|
protected |
Definition at line 109 of file synchronized_string_parameter.cpp.
|
protected |
Definition at line 147 of file synchronized_string_parameter.cpp.
|
protected |
Definition at line 121 of file synchronized_string_parameter.cpp.
|
protected |
Definition at line 82 of file synchronized_string_parameter.h.
|
protected |
Definition at line 76 of file synchronized_string_parameter.h.
|
protected |
Definition at line 75 of file synchronized_string_parameter.h.
|
protected |
Definition at line 77 of file synchronized_string_parameter.h.
|
protected |
Definition at line 80 of file synchronized_string_parameter.h.
|
protected |
Definition at line 79 of file synchronized_string_parameter.h.