MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Adds testing capabilities of Behaviors with context to any test fixture. More...
#include <test_behavior.hpp>
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::BehaviorContext & | behaviorContext () |
std::shared_ptr< behaviors::BehaviorContext > | behaviorContextSharedPtr () |
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 () |
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.
BehaviorT | The class of the Behavior under test. |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlineprotected |
|
inline |
|
inline |
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.
name | The name of the Behavior. |
input_port_setter_generator | A port setter map generator defining the expected input ports. |
output_port_setter_generator | A port setter map generator defining the expected output ports. |
WrongBehaviorPortsException | if the Behavior does not define exactly the expected ports. |
|
protected |
|
inline |
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.
objective_library_directories | Directories where the test should search for data and/or write data to. |
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.
stamp | Timestamp of the transform. |
parent_frame | Frame from which the transform is expressed. |
child_frame | Child frame described by the transform with respect to the parent frame. |
transform | Transform from the parent frame to the child frame. |
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.
transform_msg | The stamped transform message. |