SMACC2
Loading...
Searching...
No Matches
cb_move_end_effector_relative.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_geometry_msgs/tf2_geometry_msgs.h>
22#include <geometry_msgs/msg/quaternion_stamped.hpp>
24
25#include <tf2/impl/utils.h>
26#include <tf2/transform_datatypes.h>
27#include <tf2/utils.h>
28#include <future>
29
31
33{
35
36CbMoveEndEffectorRelative::CbMoveEndEffectorRelative(geometry_msgs::msg::Transform transform)
37: transform_(transform)
38{
39}
40
42{
43 RCLCPP_INFO_STREAM(
44 getLogger(),
45 "[CbMoveEndEffectorRelative] Transform end effector pose relative: " << transform_);
46
48
49 if (this->group_)
50 {
51 moveit::planning_interface::MoveGroupInterface move_group(
52 getNode(), moveit::planning_interface::MoveGroupInterface::Options(*(this->group_)));
53 this->moveRelative(move_group, this->transform_);
54 }
55 else
56 {
58 }
59}
60
62
64 moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
65 geometry_msgs::msg::Transform & transformOffset)
66{
67 auto referenceStartPose = moveGroupInterface.getCurrentPose();
68 tf2::Quaternion currentOrientation;
69 tf2::convert(referenceStartPose.pose.orientation, currentOrientation);
70 tf2::Quaternion desiredRelativeRotation;
71
72 tf2::convert(transformOffset.rotation, desiredRelativeRotation);
73
74 auto targetOrientation = desiredRelativeRotation * currentOrientation;
75
76 geometry_msgs::msg::PoseStamped targetObjectPose = referenceStartPose;
77
78 targetObjectPose.pose.orientation = tf2::toMsg(targetOrientation);
79 targetObjectPose.pose.position.x += transformOffset.translation.x;
80 targetObjectPose.pose.position.y += transformOffset.translation.y;
81 targetObjectPose.pose.position.z += transformOffset.translation.z;
82
83 moveGroupInterface.setPlanningTime(1.0);
84
85 RCLCPP_INFO_STREAM(
86 getLogger(), "[CbMoveEndEffectorRelative] Target End efector Pose: " << targetObjectPose);
87
88 moveGroupInterface.setPoseTarget(targetObjectPose);
89 moveGroupInterface.setPoseReferenceFrame("map");
90
91 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
92 bool success =
93 (moveGroupInterface.plan(computedMotionPlan) ==
94 moveit::planning_interface::MoveItErrorCode::SUCCESS);
95 RCLCPP_INFO(getLogger(), "Success Visualizing plan 1 (pose goal) %s", success ? "" : "FAILED");
96
97 if (success)
98 {
99 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
100
101 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
102 {
103 RCLCPP_INFO(getLogger(), "[CbMoveEndEffectorRelative] motion execution succeeded");
105 this->postSuccessEvent();
106 }
107 else
108 {
109 moveGroupInterface.setPoseTarget(
110 referenceStartPose); // undo to avoid abort-repeat state issues with this relative motion
111 RCLCPP_INFO(getLogger(), "[CbMoveEndEffectorRelative] motion execution failed");
113 this->postFailureEvent();
114 }
115 }
116 else
117 {
118 moveGroupInterface.setPoseTarget(
119 referenceStartPose); //undo since we did not executed the motion
120 RCLCPP_INFO(getLogger(), "[CbMoveEndEffectorRelative] motion execution failed");
122 this->postFailureEvent();
123 }
124}
125} // namespace cl_move_group_interface
void moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupinterface, geometry_msgs::msg::Transform &transformOffset)
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)