Given an input PoseStamped representing a grasp pose selected on an object, get the three Subframes that define a Grasp Screw Motion (grab and twist about an axis) where the object is grabbed and rotated by grasp_rotation_z_radians amount.
More...
#include <get_grasp_and_twist_subframes.hpp>
Given an input PoseStamped representing a grasp pose selected on an object, get the three Subframes that define a Grasp Screw Motion (grab and twist about an axis) where the object is grabbed and rotated by grasp_rotation_z_radians amount.
Assumes that the Z- axis of the grasp pose matches the normal vector of the front face of the object.
Data Port Name | Port Type | Object Type |
target_grasp_pose | Input | geometry_msgs::msg::PoseStamped |
grasp_rotation_z_radians | Input | double |
grasp_and_twist_subframes | Output | std::vector<moveit_studio_vision_msgs::msg::ObjectSubframe> |
◆ GetGraspAndTwistSubframes()
moveit_studio::behaviors::GetGraspAndTwistSubframes::GetGraspAndTwistSubframes |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::GetGraspAndTwistSubframes::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::GetGraspAndTwistSubframes::providedPorts |
( |
| ) |
|
|
static |
◆ tick()
BT::NodeStatus moveit_studio::behaviors::GetGraspAndTwistSubframes::tick |
( |
| ) |
|
|
override |
The documentation for this class was generated from the following files: