25#include <moveit_msgs/msg/collision_object.hpp>
67 moveit_msgs::msg::CollisionObject targetCollisionObject;
74 targetCollisionObject.operation = moveit_msgs::msg::CollisionObject::ADD;
75 targetCollisionObject.header.stamp =
getNode()->now();
89 "[CbAttachObject] Object not found in grasping component: " <<
targetObjectName_);
Client behavior that attaches a collision object to the robot gripper.
void onEntry() override
Called when the behavior is entered.
std::string targetObjectName_
Name of the target object to attach.
void onExit() override
Called when the behavior is exited.
CbAttachObject()
Default constructor.
CbAttachObject(std::string targetObjectName)
Constructor with object name.
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
std::shared_ptr< moveit::planning_interface::PlanningSceneInterface > planningSceneInterface
std::vector< std::string > fingerTipNames
std::optional< std::string > currentAttachedObjectName
bool getGraspingObject(std::string name, moveit_msgs::msg::CollisionObject &object)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)