MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::BehaviorContext Struct Reference

The BehaviorContext struct contains shared resources that are common between all instances of Behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. More...

#include <behavior_context.hpp>

Public Member Functions

 BehaviorContext (const std::shared_ptr< rclcpp::Node > &node_in, bool tf2_spin_thread=true, bool load_robot_model=false)
 
 BehaviorContext (const std::shared_ptr< rclcpp::Node > &node_in, std::unique_ptr< moveit_studio::behavior::LoggerBase > logger, bool tf2_spin_thread=true, bool load_robot_model=false)
 
 BehaviorContext (const BehaviorContext &)=delete
 
 BehaviorContext (BehaviorContext &&)=delete
 
BehaviorContextoperator= (const BehaviorContext &)=delete
 
BehaviorContextoperator= (BehaviorContext &&)=delete
 

Public Attributes

const std::shared_ptr< rclcpp::Node > node
 A const shared pointer to a RCLCPP Node. This points to an instance of a Node provided when constructing the BehaviorContext. More...
 
const std::shared_ptr< rclcpp::CallbackGroup > callback_group_mutually_exclusive
 A const shared pointer mutually-exclusive callback group. More...
 
const std::shared_ptr< rclcpp::CallbackGroup > reentrant_callback_group
 A const shared pointer reentrant callback group. More...
 
const std::unique_ptr< moveit_studio::behavior::LoggerBaselogger
 A const unique pointer to a logger for reporting messages to the UI. More...
 
tf2_ros::Buffer transform_buffer
 Transform buffer, listener, and broadcaster to interface with TF. More...
 
tf2_ros::TransformListener transform_listener
 
tf2_ros::TransformBroadcaster transform_broadcaster
 
moveit::core::RobotModelPtr robot_model
 The robot model, may be nullptr if the BehaviorContext was created with load_robot_model=false. More...
 

Detailed Description

The BehaviorContext struct contains shared resources that are common between all instances of Behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode.

The BehaviorContext struct won't load a robot model by default. This is to avoid the cost of loading the robot model when it's not actually needed (e.g. tests), or needing to consume a timeout waiting for the model to be available. If a robot model is needed (e.g. when running on an actual robot), set load_robot_model=true when constructing the BehaviorContext. If load_robot_model=true and the robot model fails to load, the BehaviorContext will throw an exception and the program will terminate.

Constructor & Destructor Documentation

◆ BehaviorContext() [1/4]

moveit_studio::behaviors::BehaviorContext::BehaviorContext ( const std::shared_ptr< rclcpp::Node > &  node_in,
bool  tf2_spin_thread = true,
bool  load_robot_model = false 
)
inline

◆ BehaviorContext() [2/4]

moveit_studio::behaviors::BehaviorContext::BehaviorContext ( const std::shared_ptr< rclcpp::Node > &  node_in,
std::unique_ptr< moveit_studio::behavior::LoggerBase logger,
bool  tf2_spin_thread = true,
bool  load_robot_model = false 
)
inline

◆ BehaviorContext() [3/4]

moveit_studio::behaviors::BehaviorContext::BehaviorContext ( const BehaviorContext )
delete

◆ BehaviorContext() [4/4]

moveit_studio::behaviors::BehaviorContext::BehaviorContext ( BehaviorContext &&  )
delete

Member Function Documentation

◆ operator=() [1/2]

BehaviorContext& moveit_studio::behaviors::BehaviorContext::operator= ( BehaviorContext &&  )
delete

◆ operator=() [2/2]

BehaviorContext& moveit_studio::behaviors::BehaviorContext::operator= ( const BehaviorContext )
delete

Member Data Documentation

◆ callback_group_mutually_exclusive

const std::shared_ptr<rclcpp::CallbackGroup> moveit_studio::behaviors::BehaviorContext::callback_group_mutually_exclusive

A const shared pointer mutually-exclusive callback group.

Marked const to prevent Behaviors that can access BehaviorContext from changing it.

◆ logger

const std::unique_ptr<moveit_studio::behavior::LoggerBase> moveit_studio::behaviors::BehaviorContext::logger

A const unique pointer to a logger for reporting messages to the UI.

Marked const to prevent Behaviors that can access BehaviorContext from changing it.

◆ node

const std::shared_ptr<rclcpp::Node> moveit_studio::behaviors::BehaviorContext::node

A const shared pointer to a RCLCPP Node. This points to an instance of a Node provided when constructing the BehaviorContext.

Marked const to prevent Behaviors that can access BehaviorContext from changing it.

◆ reentrant_callback_group

const std::shared_ptr<rclcpp::CallbackGroup> moveit_studio::behaviors::BehaviorContext::reentrant_callback_group

A const shared pointer reentrant callback group.

Marked const to prevent Behaviors that can access BehaviorContext from changing it.

◆ robot_model

moveit::core::RobotModelPtr moveit_studio::behaviors::BehaviorContext::robot_model

The robot model, may be nullptr if the BehaviorContext was created with load_robot_model=false.

if load_robot_model=true, this is guaranteed to be a valid pointer.

◆ transform_broadcaster

tf2_ros::TransformBroadcaster moveit_studio::behaviors::BehaviorContext::transform_broadcaster

◆ transform_buffer

tf2_ros::Buffer moveit_studio::behaviors::BehaviorContext::transform_buffer

Transform buffer, listener, and broadcaster to interface with TF.

◆ transform_listener

tf2_ros::TransformListener moveit_studio::behaviors::BehaviorContext::transform_listener

The documentation for this struct was generated from the following file: