SMACC2
Loading...
Searching...
No Matches
cb_end_effector_rotate.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <tf2_ros/buffer.h>
22#include <tf2_ros/transform_listener.h>
25
26#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
27
28#include <ament_index_cpp/get_package_share_directory.hpp>
29
30using namespace std::chrono_literals;
31
33{
34CbEndEffectorRotate::CbEndEffectorRotate(double deltaRadians, std::optional<std::string> tipLink)
35: CbCircularPivotMotion(tipLink)
36{
37 deltaRadians_ = deltaRadians;
38}
39
41
43{
44 // autocompute pivot pose
45 tf2_ros::Buffer tfBuffer(getNode()->get_clock());
46 tf2_ros::TransformListener tfListener(tfBuffer);
47
48 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
49
50 int attempts = 3;
51
53 if (!tipLink_)
54 {
55 tipLink_ = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
56 RCLCPP_WARN_STREAM(
57 getLogger(),
58 "[" << getName() << "] tip unspecified, using default end effector: " << *tipLink_);
59 }
60
61 while (attempts > 0)
62 {
63 try
64 {
65 //auto pivotFrameName = this->movegroupClient_->moveGroupClientInterface->getPlanningFrame();
66 auto pivotFrameName = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
67
68 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
69
70 tf2::fromMsg(
71 tfBuffer.lookupTransform(pivotFrameName, *tipLink_, rclcpp::Time(), rclcpp::Duration(10s)),
72 endEffectorInPivotFrame);
73
74 tf2::toMsg(endEffectorInPivotFrame, this->planePivotPose_.pose);
75 this->planePivotPose_.header.frame_id = endEffectorInPivotFrame.frame_id_;
76 this->planePivotPose_.header.stamp =
77 rclcpp::Time(endEffectorInPivotFrame.stamp_.time_since_epoch().count());
78 break;
79 }
80 catch (const std::exception & e)
81 {
82 RCLCPP_ERROR_STREAM(getLogger(), e.what() << ". Attempt countdown: " << attempts);
83 rclcpp::Duration(500ms);
84 attempts--;
85 }
86 }
87
88 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] pivotPose: " << planePivotPose_);
89
90 RCLCPP_INFO_STREAM(
91 getLogger(), "[" << getName() << "] calling base CbCircularPivotMotion::onEntry");
93}
94} // namespace cl_move_group_interface
CbEndEffectorRotate(double deltaRadians, std::optional< std::string > tipLink=std::nullopt)
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)