MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::CalculatePoseOffset Class Referencefinal

Calculates the offset transform from source_pose to destination_pose. This can be used to measure the distance between two poses and returns the result relative to the source_pose. More...

#include <calculate_pose_offset.hpp>

Inheritance diagram for moveit_studio::behaviors::CalculatePoseOffset:
Collaboration diagram for moveit_studio::behaviors::CalculatePoseOffset:

Public Member Functions

 CalculatePoseOffset (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for CalculatePoseOffset behavior. More...
 
BT::NodeStatus tick () override
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
 SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. More...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 Custom tree nodes that have input and/or output ports must define them in this static function. More...
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Calculates the offset transform from source_pose to destination_pose. This can be used to measure the distance between two poses and returns the result relative to the source_pose.

This behavior will fail if the frame_id for the source and destination frames are not connected.

Data Port Name Port Type Object Type
source_pose input geometry_msgs::msg::PoseStamped
destination_pose input geometry_msgs::msg::PoseStamped
source_to_destination_pose output geometry_msgs::msg::Pose

Constructor & Destructor Documentation

◆ CalculatePoseOffset()

moveit_studio::behaviors::CalculatePoseOffset::CalculatePoseOffset ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

Constructor for CalculatePoseOffset behavior.

Parameters
nameName of the node. Must match the name used for this node in the behavior tree definition file (the .xml file).
configNode configuration. Only used here because the BehaviorTree.CPP expects constructor signature with name and config first before custom constructor parameters.
shared_resourcesProvides access to common resources such as the node handle and failure logger that are shared between all the behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode.

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::CalculatePoseOffset::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::CalculatePoseOffset::providedPorts ( )
static

Custom tree nodes that have input and/or output ports must define them in this static function.

This function must be static. It is a requirement set by the BehaviorTree.CPP library.

Returns
List of ports with the names and port info. The return value is for the internal use of the behavior tree.

◆ tick()

BT::NodeStatus moveit_studio::behaviors::CalculatePoseOffset::tick ( )
override

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