SMACC2
Loading...
Searching...
No Matches
cb_move_end_effector.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 <moveit/kinematic_constraints/utils.h>
22#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
23#include <future>
24
25#include <tf2/impl/utils.h>
28
29using namespace std::chrono_literals;
30
32{
34
36 geometry_msgs::msg::PoseStamped target_pose, std::string tip_link)
37: targetPose(target_pose)
38{
39 tip_link_ = tip_link;
40}
41
43{
45
46 if (this->group_)
47 {
48 RCLCPP_DEBUG(
49 getLogger(), "[CbMoveEndEfector] new thread started to move absolute end effector");
50 moveit::planning_interface::MoveGroupInterface move_group(getNode(), *group_);
51 this->moveToAbsolutePose(move_group, targetPose);
52 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEfector] to move absolute end effector thread destroyed");
53 }
54 else
55 {
56 RCLCPP_DEBUG(
57 getLogger(), "[CbMoveEndEfector] new thread started to move absolute end effector");
59 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEfector] to move absolute end effector thread destroyed");
60 }
61}
62
64 moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
65 geometry_msgs::msg::PoseStamped & targetObjectPose)
66{
67 // auto & planningSceneInterface = movegroupClient_->planningSceneInterface;
68 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEffector] Synchronous sleep of 1 seconds");
69 rclcpp::sleep_for(500ms);
70
71 moveGroupInterface.setPlanningTime(1.0);
72
73 RCLCPP_INFO_STREAM(
74 getLogger(), "[CbMoveEndEffector] Target End efector Pose: " << targetObjectPose);
75
76 moveGroupInterface.setPoseTarget(targetObjectPose, tip_link_);
77 moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);
78
79 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
80 bool success =
81 (moveGroupInterface.plan(computedMotionPlan) ==
82 moveit::planning_interface::MoveItErrorCode::SUCCESS);
83 RCLCPP_INFO(
84 getLogger(), "[CbMoveEndEffector] Success Visualizing plan 1 (pose goal) %s",
85 success ? "" : "FAILED");
86
87 if (success)
88 {
89 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
90
91 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
92 {
93 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] motion execution succeeded");
95 this->postSuccessEvent();
96 }
97 else
98 {
99 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] motion execution failed");
101 this->postFailureEvent();
102 }
103 }
104 else
105 {
106 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] motion execution failed");
108 this->postFailureEvent();
109 }
110
111 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEffector] Synchronous sleep of 1 seconds");
112 rclcpp::sleep_for(500ms);
113
114 return success;
115}
116
117} // namespace cl_move_group_interface
bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::msg::PoseStamped &targetObjectPose)
geometry_msgs::msg::PoseStamped targetPose
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)