MoveIt Pro Behavior Interface  5.0.1
Library for developing custom behaviors for use in MoveIt Pro
moveit_studio::behaviors Namespace Reference

Namespaces

 check_for_error_utils
 

Classes

class  ActionClientBehaviorBase
 A base class for behaviors which need to send a goal to a ROS action client and wait for a result. If the behavior is halted before the action result is received, the action goal will be canceled. More...
 
class  AsyncBehaviorBase
 A base class for behaviors which need to asynchronously run a function that might take a long time to complete. More...
 
struct  BehaviorContext
 The BehaviorContext struct contains shared resources that are common between all instances of Behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. More...
 
class  ClockInterfaceBase
 A base class which provides an interface for retrieving timepoints from a monotonic clock. More...
 
class  SteadyClockInterface
 Implementation of ClockInterfaceBase for std::chrono::steady_clock. More...
 
class  ForEach
 A class template for creating a behavior tree decorator node to help iterate through a vector of items. More...
 
class  GetMessageFromTopicBehaviorBase
 Base class for Behaviors that get the latest message from a topic specified on an input data port and set that message to an output data port. More...
 
class  LoadMultipleFromYaml
 Loads types from a YAML file, and returns them as a vector in an output port. More...
 
class  LoadFromYaml
 Loads a type from a YAML file, and returns it in an output port. More...
 
class  PublisherInterfaceBase
 Defines an interface to a publisher that sends a message to a topic. More...
 
class  RclcppPublisherInterface
 Implementation of the publisher interface for a rclcpp publisher. More...
 
class  SaveToYaml
 Save the contents of a ROS 2 message type to a YAML file in a specified namespace. Note: This Behavior template saves the pose into the ~/.config/moveit_pro/robot_config/objectives folder. More...
 
class  SendMessageToTopicBehaviorBase
 Base class for Behaviors that send a message to a topic. The message contents and topic name are specified as input ports. More...
 
class  ServiceClientBehaviorBase
 A base class for behaviors which need to send a request to a ROS service client and wait for a result. More...
 
class  ClientInterfaceBase
 Provides an interface to a service client that can send a single request at a time. WARNING - This class currently does not support calling syncSendRequest function asynchronously from multiple threads. More...
 
class  RclcppClientInterface
 Implements ClientInterfaceBase for the rclcpp service client. More...
 
class  SharedResourcesNode
 The SharedResourcesNode class provides a BehaviorContext object when constructing a BehaviorTree.Cpp node. More...
 
class  SharedResourcesNodeLoaderBase
 The SharedResourcesNodeLoaderBase class is a base class for Behavior loader plugins that register Behaviors inheriting from SharedResourcesNode. More...
 

Functions

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...
 
template<class T >
void parseROSMessage (const YAML::Node &node, const InterfaceTypeName &interface_type, T &rhs)
 Templated function to parse any ROS message from a YAML Node. More...
 
template<typename T >
void saveROSMessage (YAML::Node &node, const InterfaceTypeName &interface_type, T msg)
 Templated function to save any ROS message to a YAML Node. More...
 
template<typename T >
tl::expected< T, std::string > parseParameter (const YAML::Node &yaml, const std::string &parameter_name)
 Helper function for parsing a parameter from a YAML::Node. More...
 

Variables

constexpr auto kDescriptionLoadFromYaml
 
constexpr auto kDescriptionLoadJointTrajectoryFromYaml
 
constexpr auto kDescriptionLoadPoseStampedFromYaml = "<p>Loads a PoseStamped message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadPoseStampedVectorFromYaml
 
constexpr auto kDescriptionLoadSubframesFromYaml
 
constexpr auto kDescriptionSaveToYaml
 
constexpr auto kDescriptionSavePoseToYaml
 
constexpr auto kDescriptionSavePoseStampedToYaml
 
constexpr auto kDescriptionSaveJointTrajectoryToYaml
 

Function Documentation

◆ clientMustBeRecreated() [1/2]

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:

  1. 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.
  2. 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
clientThe service client to check
new_service_nameThe 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.

◆ clientMustBeRecreated() [2/2]

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:

  1. 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.
  2. 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
clientThe action client to check
new_action_nameThe 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.

◆ getDefaultNodeBuilder()

template<typename T >
BT::NodeBuilder moveit_studio::behaviors::getDefaultNodeBuilder ( )
inline

Helper function to create a BT::NodeBuilder for a behavior tree node with the default constructor signature.

Template Parameters
TCreate a builder for this type of node. Must be derived from BT::TreeNode.
Returns
A BT::NodeBuilder that creates a node of type T.

◆ getSharedResourcesNodeBuilder()

template<typename T >
BT::NodeBuilder moveit_studio::behaviors::getSharedResourcesNodeBuilder ( const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources)
inline

Helper function to create a BT::NodeBuilder for a behavior tree node which takes shared_ptr<BehaviorContext> as an additional constructor parameter.

Parameters
shared_resourcesA shared_ptr to an instance of BehaviorContext, which will be provided when creating the behaviors registered by this function.
Template Parameters
TCreate a builder for this type of node. Must be derived from moveit_studio::behaviors::SharedResourcesNode.
Returns
A BT::NodeBuilder that creates a node of type T.

◆ maybe_error() [1/2]

template<typename... Args>
std::optional<std::string> moveit_studio::behaviors::maybe_error ( BT::Expected< Args >...  args)
inline

Check if any of the provided inputs represent error states and, if so, return their error messages.

This was inspired by fp's maybe_error function: https://github.com/tylerjw/fp/blob/b4bf17c2f7a99c07b6ab9b8706357572e960d638/include/fp/result.hpp#L216-L236

Parameters
argsOne or more BT::Expecteds (i.e., results from getInput)
Returns
std::optional wrapping std::string. If all of the inputs in args have values, returns std::nullopt. If one or more of the inputs in args contains an error state instead of a value, return a string that contains the concatenated error messages of all inputs that did not contain a value.

◆ maybe_error() [2/2]

template<typename E , typename... Args>
constexpr std::optional<E> moveit_studio::behaviors::maybe_error ( tl::expected< Args, E >...  args)
constexpr

Tests if any of the expected args passed in has an error.

This was adapted from fp's maybe_error function with a small modification.

Parameters
[in]Thetl::expected<T, E> variables. All have to use the same error type.
Template Parameters
EThe error type
ArgsThe value types for the tl::expected<T, E> args
Returns
The first error found or nothing

◆ parseParameter()

template<typename T >
tl::expected<T, std::string> moveit_studio::behaviors::parseParameter ( const YAML::Node &  yaml,
const std::string &  parameter_name 
)

Helper function for parsing a parameter from a YAML::Node.

Template Parameters
TType of the parameter.
Parameters
yamlParsed YAML file for an objective containing the parameters for every parameterized behavior in the objective.
parameter_nameParameter name within the YAML file.
Returns
Parsed parameter if parsing it succeeded and it has a valid value. Error otherwise.

◆ parseROSMessage()

template<class T >
void moveit_studio::behaviors::parseROSMessage ( const YAML::Node &  node,
const InterfaceTypeName &  interface_type,
T &  rhs 
)

Templated function to parse any ROS message from a YAML Node.

Template Parameters
theROS message type to load.

This uses the dynamic_message_introspection package to parse any given ROS message from a YAML file. Throws an exception if the message can't be parsed, e.g. if the YAML contains fields not corresponding to the given message type. Example of use: geometry_msgs::msg::Pose pose; parseROSMessage(yaml_node, InterfaceTypeName{"geometry_msgs", "Pose"}, pose);

◆ registerBehavior() [1/2]

template<typename T >
void moveit_studio::behaviors::registerBehavior ( BT::BehaviorTreeFactory &  factory,
const std::string &  name 
)
inline

Helper function to register a behavior with the default constructor signature with a BT::BehaviorTreeFactory.

Parameters
factoryRegister behaviors with this factory.
nameThe name to use when registering this type of behavior. It is good practice to make this name match the name of the class (e.g., moveit_studio::behaviors::PlanMTCTask is registered as "PlanMTCTask").
Template Parameters
TRegister a behavior of this type.

◆ registerBehavior() [2/2]

template<typename T >
void moveit_studio::behaviors::registerBehavior ( BT::BehaviorTreeFactory &  factory,
const std::string &  name,
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources 
)
inline

Helper function to register a behavior derived from SharedResourcesNode with a BT::BehaviorTreeFactory.

Parameters
factoryRegister behaviors with this factory.
nameThe name to use when registering this type of behavior. It is good practice to make this name match the name of the class (e.g., moveit_studio::behaviors::PlanMTCTask is registered as "PlanMTCTask").
shared_resourcesA shared_ptr to an instance of BehaviorContext, which will be provided when creating the behaviors registered by this function.
Template Parameters
TRegister a behavior of this type.

◆ saveROSMessage()

template<typename T >
void moveit_studio::behaviors::saveROSMessage ( YAML::Node &  node,
const InterfaceTypeName &  interface_type,
msg 
)

Templated function to save any ROS message to a YAML Node.

Template Parameters
theROS message type to save.

This uses the dynamic_message_introspection package to serialize any given ROS message to a YAML file. Throws an exception if the message can't be saved, e.g. if the ROS message contains fields not corresponding to the given message type. Example of use: geometry_msgs::msg::Pose pose; saveROSMessage(pose, InterfaceTypeName{"geometry_msgs", "Pose"}, yaml_node);

◆ shouldRecreatePublisher()

bool moveit_studio::behaviors::shouldRecreatePublisher ( const std::shared_ptr< rclcpp::PublisherBase > &  publisher,
const std::string_view  topic_name,
const size_t  queue_size,
const rclcpp::ReliabilityPolicy  reliability_policy 
)
inline

Compare a publisher's current configuration to the desired new configuration to determine if the publisher needs to be recreated.

This checks two criteria:

  1. Is the publisher a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the publisher must be created in that case.
  2. If the publisher already exists, does it publish to the right topic? If not, the publisher needs to be reinitialized to use the new topic name.
  3. If the publisher already exists, does its queue_size and reliability QoS settings match the new queue_size and reliability? If not, the publisher needs to be reinitialized with these new QoS settings.
Parameters
publisherThe existing publisher to check.
topic_nameThe topic name for the new configuration.
queue_sizeThe queue size for the new configuration.
reliability_policyThe reliability policy for the new configuration
Returns
True if the publisher must be recreated, and false if the publisher's current configuration already satisfies the new configuration.

◆ shouldRecreateSubscriber()

template<typename MessageT >
bool moveit_studio::behaviors::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.

This checks three criteria:

  1. Is the subscriber a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the subscriber must be created in that case.
  2. If the subscriber already exists, does it listen on the right topic? If not, the client needs to be reinitialized to use the new action name.
  3. If the subscriber already exists, does it use the same reliability QoS setting as the publisher? If not, the subscriber needs to be reinitialized using the same reliability QoS setting as the publisher.
Parameters
subscriberThe existing subscriber to check.
topic_nameThe topic name for the new configuration.
publisher_qosThe publisher's QoS for the new configuration.
Template Parameters
MessageTThe ROS message type used to specialize this function.
Returns
True if the subscriber must be recreated, and false if the subscriber's current configuration already satisfies the new configuration.

◆ waitForPublisher()

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
nodeNode used to retrieve publisher info.
topic_nameName 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.

Variable Documentation

◆ kDescriptionLoadFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of objects from a file, converts it and their names in the file to a vector of messages, and "
"writes that to an output data port.</p>"

◆ kDescriptionLoadJointTrajectoryFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadJointTrajectoryFromYaml
inlineconstexpr
Initial value:
=
"<p>Accepts a joint trajectory YAML file name, parses the file, and outputs a JointTrajectory ROS message object "
"created from the file contents.</p>"

◆ kDescriptionLoadPoseStampedFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseStampedFromYaml = "<p>Loads a PoseStamped message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadPoseStampedVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseStampedVectorFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of PoseStamped messages from a YAML file.</p>"

◆ kDescriptionLoadSubframesFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadSubframesFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of Subframes from a file, converts it and their names in the file to a vector of ROS "
"moveit_studio_vision_msgs/ObjectSubframe messages, and writes that to an output data port.</p>"

◆ kDescriptionSaveJointTrajectoryToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveJointTrajectoryToYaml
inlineconstexpr
Initial value:
=
"<p>Accepts a JointTrajectory ROS message object, a namespace, and a file name. Converts and saves the joint "
"trajectory message as a YAML file in the objectives directory at the provided file name and under the provided "
"namespace within the file.</p>"

◆ kDescriptionSavePoseStampedToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSavePoseStampedToYaml
inlineconstexpr
Initial value:
=
"<p>Write a pose given as a `geometry_msgs::msg::PoseStamped` message to a YAML file.</p>"

◆ kDescriptionSavePoseToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSavePoseToYaml
inlineconstexpr
Initial value:
=
"<p>Write a pose given as a `geometry_msgs::msg::Pose` message to a YAML file.</p>"

◆ kDescriptionSaveToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveToYaml
inlineconstexpr
Initial value:
=
"<p>Accepts a ROS message object, a namespace, and a file name. Converts and saves the message as a YAML file in "
"the Objectives directory at the provided file name and under the provided namespace within the file.</p>"