|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
#include <tf2_ros/buffer.h>#include <tf2_ros/transform_listener.h>#include <moveit_studio_behavior/behaviors/core/calculate_pose_offset.hpp>#include <moveit_studio_behavior_interface/behavior_context.hpp>#include <moveit_studio_behavior_interface/get_required_ports.hpp>#include <moveit_studio_behavior_interface/metadata_fields.hpp>#include <tf2_eigen/tf2_eigen.hpp>
Namespaces | |
| namespace | moveit_studio |
| namespace | moveit_studio::behaviors |
Functions | |
| tl::expected< void, std::string > | canTransformCheck (const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, const std::string &source_frame_id, const std::string &destination_frame_id) |
| tl::expected< void, std::string > | preCalculationChecks (const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, const geometry_msgs::msg::PoseStamped &source_pose, const geometry_msgs::msg::PoseStamped &destination_pose) |
| Performs checks to see if the pose offset is actually possible to calculate. | |
| geometry_msgs::msg::PoseStamped | poseOffset (const geometry_msgs::msg::TransformStamped &transform, const geometry_msgs::msg::PoseStamped &source_pose, const geometry_msgs::msg::PoseStamped &destination_pose) |
| Calculates the pose offset given the transform between poses, the source pose, and destination pose. | |
| tl::expected< void, std::string > canTransformCheck | ( | const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > & | shared_resources, |
| const std::string & | source_frame_id, | ||
| const std::string & | destination_frame_id | ||
| ) |
| geometry_msgs::msg::PoseStamped poseOffset | ( | const geometry_msgs::msg::TransformStamped & | transform, |
| const geometry_msgs::msg::PoseStamped & | source_pose, | ||
| const geometry_msgs::msg::PoseStamped & | destination_pose | ||
| ) |
Calculates the pose offset given the transform between poses, the source pose, and destination pose.
| transform | The transform between the source and destination frame |
| source_pose | The source pose |
| destination_pose | The destination pose |
| tl::expected< void, std::string > preCalculationChecks | ( | const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > & | shared_resources, |
| const geometry_msgs::msg::PoseStamped & | source_pose, | ||
| const geometry_msgs::msg::PoseStamped & | destination_pose | ||
| ) |
Performs checks to see if the pose offset is actually possible to calculate.
| shared_resources | The Behavior Context used for ROS operations |
| source_pose | The source pose |
| destination_pose | The destination pose |