21#include <tf2_ros/buffer.h>
22#include <tf2_ros/transform_listener.h>
26#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
28#include <ament_index_cpp/get_package_share_directory.hpp>
30using namespace std::chrono_literals;
45 tf2_ros::Buffer tfBuffer(
getNode()->get_clock());
46 tf2_ros::TransformListener tfListener(tfBuffer);
48 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
58 "[" <<
getName() <<
"] tip unspecified, using default end effector: " << *
tipLink_);
68 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
71 tfBuffer.lookupTransform(pivotFrameName, *
tipLink_, rclcpp::Time(), rclcpp::Duration(10
s)),
72 endEffectorInPivotFrame);
75 this->
planePivotPose_.header.frame_id = endEffectorInPivotFrame.frame_id_;
77 rclcpp::Time(endEffectorInPivotFrame.stamp_.time_since_epoch().count());
80 catch (
const std::exception & e)
82 RCLCPP_ERROR_STREAM(
getLogger(), e.what() <<
". Attempt countdown: " << attempts);
83 rclcpp::Duration(500ms);
91 getLogger(),
"[" <<
getName() <<
"] calling base CbCircularPivotMotion::onEntry");
geometry_msgs::msg::PoseStamped planePivotPose_
virtual ~CbEndEffectorRotate()
virtual void onEntry() override
CbEndEffectorRotate(double deltaRadians, std::optional< std::string > tipLink=std::nullopt)
std::optional< std::string > tipLink_
virtual void onEntry() override
ClMoveGroup * movegroupClient_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
std::string getName() const
virtual rclcpp::Logger getLogger()
virtual rclcpp::Node::SharedPtr getNode()
void requiresClient(SmaccClientType *&storage)