30CbAttachObject::CbAttachObject() {}
32void CbAttachObject::onEntry()
35 this->requiresClient(moveGroup);
38 this->requiresComponent(graspingComponent);
42 moveit_msgs::msg::CollisionObject targetCollisionObject;
44 bool found = graspingComponent->
getGraspingObject(targetObjectName_, targetCollisionObject);
48 targetCollisionObject.operation = moveit_msgs::msg::CollisionObject::ADD;
49 targetCollisionObject.header.stamp = getNode()->now();
58 RCLCPP_INFO_STREAM(getLogger(),
"[" << getName() <<
"] Grasping objectfound. attach request.");
60 this->postSuccessEvent();
65 getLogger(),
"[" << getName() <<
"] Grasping object was not found. Ignoring attach request.");
67 this->postFailureEvent();
71void CbAttachObject::onExit() {}
CbAttachObject()
Default constructor.
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
std::shared_ptr< moveit::planning_interface::PlanningSceneInterface > planningSceneInterface
std::optional< std::string > currentAttachedObjectName
std::vector< std::string > fingerTipNames
bool getGraspingObject(std::string name, moveit_msgs::msg::CollisionObject &object)