|
bool | clientMustBeRecreated (const std::shared_ptr< rclcpp_action::ClientBase > &client, const std::string_view old_action_name, const std::string_view new_action_name) |
| Compare an action client's current configuration to the desired new configuration to determine if the client needs to be recreated. More...
|
|
template<typename... Args> |
std::optional< std::string > | maybe_error (BT::Expected< Args >... args) |
| Check if any of the provided inputs represent error states and, if so, return their error messages. More...
|
|
template<typename E , typename... Args> |
constexpr std::optional< E > | maybe_error (tl::expected< Args, E >... args) |
| Tests if any of the expected args passed in has an error. More...
|
|
template<typename MessageT > |
bool | shouldRecreateSubscriber (const std::shared_ptr< rclcpp::Subscription< MessageT >> &subscriber, const std::string &topic_name, const rclcpp::QoS &publisher_qos) |
| Compare a subscriber's current configuration to the desired new configuration to determine if the subscriber needs to be recreated. More...
|
|
tl::expected< rclcpp::TopicEndpointInfo, std::string > | waitForPublisher (const std::shared_ptr< rclcpp::Node > &node, const std::string &topic_name) |
| Waits for a publisher to be advertised on the provided topic, and gets the TopicEndpointInfo for the publisher once it appears. More...
|
|
bool | shouldRecreatePublisher (const std::shared_ptr< rclcpp::PublisherBase > &publisher, const std::string_view topic_name, const size_t queue_size, const rclcpp::ReliabilityPolicy reliability_policy) |
| Compare a publisher's current configuration to the desired new configuration to determine if the publisher needs to be recreated. More...
|
|
bool | clientMustBeRecreated (const std::shared_ptr< rclcpp::ClientBase > &client, const std::string_view new_service_name) |
| Compare a service client's current configuration to the desired new configuration to determine if the client needs to be recreated. More...
|
|
template<typename T > |
BT::NodeBuilder | getDefaultNodeBuilder () |
| Helper function to create a BT::NodeBuilder for a behavior tree node with the default constructor signature. More...
|
|
template<typename T > |
BT::NodeBuilder | getSharedResourcesNodeBuilder (const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources) |
| Helper function to create a BT::NodeBuilder for a behavior tree node which takes shared_ptr<BehaviorContext> as an additional constructor parameter. More...
|
|
template<typename T > |
void | registerBehavior (BT::BehaviorTreeFactory &factory, const std::string &name) |
| Helper function to register a behavior with the default constructor signature with a BT::BehaviorTreeFactory. More...
|
|
template<typename T > |
void | registerBehavior (BT::BehaviorTreeFactory &factory, const std::string &name, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources) |
| Helper function to register a behavior derived from SharedResourcesNode with a BT::BehaviorTreeFactory. More...
|
|
bool moveit_studio::behaviors::clientMustBeRecreated |
( |
const std::shared_ptr< rclcpp::ClientBase > & |
client, |
|
|
const std::string_view |
new_service_name |
|
) |
| |
|
inline |
Compare a service client's current configuration to the desired new configuration to determine if the client needs to be recreated.
This checks two criteria:
- Is the client a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the client must be created in that case.
- If the client already exists, does it communicate on a topic with the same name as the name provided through the input data port? If not, the client needs to be reinitialized to use the new topic.
This does NOT check if the client's QoS settings match the ones used by the server, because ServiceClientBehaviorBase always creates clients using the rmw_qos_profile_services_default
QoS profile. Also, it is unlikely that a ROS 2 service server would use customized QoS settings.
- Parameters
-
client | The service client to check |
new_service_name | The new service name |
- Returns
- True if the client must be recreated to satisfy the new configuration. False if the client's current configuration already satisfies the new configuration.
bool moveit_studio::behaviors::clientMustBeRecreated |
( |
const std::shared_ptr< rclcpp_action::ClientBase > & |
client, |
|
|
const std::string_view |
old_action_name, |
|
|
const std::string_view |
new_action_name |
|
) |
| |
|
inline |
Compare an action client's current configuration to the desired new configuration to determine if the client needs to be recreated.
This checks two criteria:
- Is the client a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the client must be created in that case.
- If the client already exists, does it communicate with an action with the same name as the name provided through the input data port? If not, the client needs to be reinitialized to use the new action name.
This does NOT check if the client's QoS settings match the ones used by the server, because ActionClientBehaviorBase always creates clients using the default ROS 2 action client QoS profile. It is also very complex to retrieve the QoS settings for an action server (since it's composed of a collection of services and topics). In any case action clients are almost always created with default QoS settings (or at the very least we've never seen one that used non-default settings).
- Parameters
-
client | The action client to check |
new_action_name | The new action name |
- Returns
- True if the client must be recreated to satisfy the new configuration. False if the client's current configuration already satisfies the new configuration.
tl::expected< rclcpp::TopicEndpointInfo, std::string > moveit_studio::behaviors::waitForPublisher |
( |
const std::shared_ptr< rclcpp::Node > & |
node, |
|
|
const std::string & |
topic_name |
|
) |
| |
Waits for a publisher to be advertised on the provided topic, and gets the TopicEndpointInfo for the publisher once it appears.
If multiple publishers are found on the same topic, this function just returns the TopicEndpointInfo for the first one in the order they were reported by the node. If multiple publishers advertise on the same topic with different reliability QoS settings the Behavior will only receive messages from the ones whose settings match the first publisher in the list. This situation will only happen if the publishers have been incorrectly configured, so this is not handled by this Behavior.
- Parameters
-
node | Node used to retrieve publisher info. |
topic_name | Name of the topic where we expect the publisher to advertise. |
- Returns
- If one or more publishers were found on the topic, returns the TopicEndpointInfo for the first publisher that was found. If no publishers were found on the topic before the timeout elapsed, return an error result.