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>
|
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 () |
|
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 |
◆ 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
-
name | Name of the node. Must match the name used for this node in the behavior tree definition file (the .xml file). |
config | Node configuration. Only used here because the BehaviorTree.CPP expects constructor signature with name and config first before custom constructor parameters. |
shared_resources | Provides 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. |
◆ 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: