MoveIt Pro Behavior Interface  5.0.1
Library for developing custom behaviors for use in MoveIt Pro
moveit_studio::test_utils::WithBehavior< BehaviorT > Class Template Reference

Adds testing capabilities of Behaviors with context to any test fixture. More...

#include <test_behavior.hpp>

Inheritance diagram for moveit_studio::test_utils::WithBehavior< BehaviorT >:

Public Member Functions

void initBehavior (const std::string &name, PortSetterMapGenerator input_port_setter_generator, PortSetterMapGenerator output_port_setter_generator)
 Initializes the Behavior under test. More...
 
BehaviorT & behavior ()
 
BT::NodeConfiguration & config ()
 
BT::Blackboard & blackboard ()
 
MockLogger & mockLogger ()
 
behaviors::BehaviorContextbehaviorContext ()
 
std::shared_ptr< behaviors::BehaviorContextbehaviorContextSharedPtr ()
 
rclcpp::Node & behaviorNode ()
 
std::shared_ptr< rclcpp::Node > behaviorNodePtr ()
 
void setTestDataDirectories (const std::vector< std::string > &objective_library_directories)
 Configure the directories that a test will read data from and/or write data to. More...
 
void setTransform (const geometry_msgs::msg::TransformStamped &transform_msg)
 Makes a transform available in the shared transform buffer. More...
 
void setTransform (const builtin_interfaces::msg::Time &stamp, std::string_view parent_frame, std::string_view child_frame, const Eigen::Isometry3d &transform)
 Makes a transform available in the shared transform buffer. More...
 

Protected Member Functions

void initBehaviorCommon (const std::string &name, PortSetterMapGenerator input_port_setter_generator, PortSetterMapGenerator output_port_setter_generator)
 
std::unique_ptr< BehaviorT > & behaviorPtr ()
 

Detailed Description

template<class BehaviorT>
class moveit_studio::test_utils::WithBehavior< BehaviorT >

Adds testing capabilities of Behaviors with context to any test fixture.

To test a Behavior with context (shared resources), a test fixture inherits from this class in addition to any base test fixture, e.g. ::testing::Test, ::moveit_studio::test_utils::RostTest, etc. The fixture automatically tests that the Behavior creates all and only the expected ports.

Template Parameters
BehaviorTThe class of the Behavior under test.

Member Function Documentation

◆ behavior()

template<class BehaviorT >
BehaviorT& moveit_studio::test_utils::WithBehavior< BehaviorT >::behavior ( )
inline

◆ behaviorContext()

template<class BehaviorT >
behaviors::BehaviorContext& moveit_studio::test_utils::WithBehavior< BehaviorT >::behaviorContext ( )
inline

◆ behaviorContextSharedPtr()

template<class BehaviorT >
std::shared_ptr<behaviors::BehaviorContext> moveit_studio::test_utils::WithBehavior< BehaviorT >::behaviorContextSharedPtr ( )
inline

◆ behaviorNode()

template<class BehaviorT >
rclcpp::Node& moveit_studio::test_utils::WithBehavior< BehaviorT >::behaviorNode ( )
inline

◆ behaviorNodePtr()

template<class BehaviorT >
std::shared_ptr<rclcpp::Node> moveit_studio::test_utils::WithBehavior< BehaviorT >::behaviorNodePtr ( )
inline

◆ behaviorPtr()

template<class BehaviorT >
std::unique_ptr<BehaviorT>& moveit_studio::test_utils::WithBehavior< BehaviorT >::behaviorPtr ( )
inlineprotected

◆ blackboard()

template<class BehaviorT >
BT::Blackboard& moveit_studio::test_utils::WithBehavior< BehaviorT >::blackboard ( )
inline

◆ config()

template<class BehaviorT >
BT::NodeConfiguration& moveit_studio::test_utils::WithBehavior< BehaviorT >::config ( )
inline

◆ initBehavior()

template<class BehaviorT >
void moveit_studio::test_utils::WithBehavior< BehaviorT >::initBehavior ( const std::string &  name,
PortSetterMapGenerator  input_port_setter_generator,
PortSetterMapGenerator  output_port_setter_generator 
)

Initializes the Behavior under test.

Call this function in your fixture's constructor, SetUp() or any of its setUp* variations.

Parameters
nameThe name of the Behavior.
input_port_setter_generatorA port setter map generator defining the expected input ports.
output_port_setter_generatorA port setter map generator defining the expected output ports.
Exceptions
WrongBehaviorPortsExceptionif the Behavior does not define exactly the expected ports.

◆ initBehaviorCommon()

template<class BehaviorT >
void moveit_studio::test_utils::WithBehavior< BehaviorT >::initBehaviorCommon ( const std::string &  name,
PortSetterMapGenerator  input_port_setter_generator,
PortSetterMapGenerator  output_port_setter_generator 
)
protected

◆ mockLogger()

template<class BehaviorT >
MockLogger& moveit_studio::test_utils::WithBehavior< BehaviorT >::mockLogger ( )
inline

◆ setTestDataDirectories()

template<class BehaviorT >
void moveit_studio::test_utils::WithBehavior< BehaviorT >::setTestDataDirectories ( const std::vector< std::string > &  objective_library_directories)

Configure the directories that a test will read data from and/or write data to.

Parameters
objective_library_directoriesDirectories where the test should search for data and/or write data to.

◆ setTransform() [1/2]

template<class BehaviorT >
void moveit_studio::test_utils::WithBehavior< BehaviorT >::setTransform ( const builtin_interfaces::msg::Time &  stamp,
std::string_view  parent_frame,
std::string_view  child_frame,
const Eigen::Isometry3d &  transform 
)

Makes a transform available in the shared transform buffer.

The Behavior will have access to the transform, as well as other Behaviors sharing the buffer.

Parameters
stampTimestamp of the transform.
parent_frameFrame from which the transform is expressed.
child_frameChild frame described by the transform with respect to the parent frame.
transformTransform from the parent frame to the child frame.

◆ setTransform() [2/2]

template<class BehaviorT >
void moveit_studio::test_utils::WithBehavior< BehaviorT >::setTransform ( const geometry_msgs::msg::TransformStamped &  transform_msg)

Makes a transform available in the shared transform buffer.

The Behavior will have access to the transform, as well as other Behaviors sharing the buffer.

Parameters
transform_msgThe stamped transform message.

The documentation for this class was generated from the following files: