SMACC2
Loading...
Searching...
No Matches
cb_move_end_effector.hpp
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#pragma once
22
23#include <tf2/impl/utils.h>
28#include <future>
30#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
31
32using namespace std::chrono_literals;
33
34namespace cl_moveit2z
35{
37{
38public:
39 geometry_msgs::msg::PoseStamped targetPose;
40 std::string tip_link_;
41 std::optional<std::string> group_;
42
44
45 CbMoveEndEffector(geometry_msgs::msg::PoseStamped target_pose, std::string tip_link = "")
46 : targetPose(target_pose)
47 {
48 tip_link_ = tip_link;
49 }
50
51 virtual void onEntry() override
52 {
54
55 if (this->group_)
56 {
57 RCLCPP_DEBUG(
58 getLogger(), "[CbMoveEndEfector] new thread started to move absolute end effector");
59 moveit::planning_interface::MoveGroupInterface move_group(getNode(), *group_);
60 this->moveToAbsolutePose(move_group, targetPose);
61 RCLCPP_DEBUG(
62 getLogger(), "[CbMoveEndEfector] to move absolute end effector thread destroyed");
63 }
64 else
65 {
66 RCLCPP_DEBUG(
67 getLogger(), "[CbMoveEndEfector] new thread started to move absolute end effector");
69 RCLCPP_DEBUG(
70 getLogger(), "[CbMoveEndEfector] to move absolute end effector thread destroyed");
71 }
72 }
73
74protected:
76 moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
77 geometry_msgs::msg::PoseStamped & targetObjectPose)
78 {
79 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEffector] Synchronous sleep of 1 seconds");
80 rclcpp::sleep_for(500ms);
81
82 // Try to use CpMotionPlanner component (preferred)
83 CpMotionPlanner * motionPlanner = nullptr;
85 motionPlanner, smacc2::ComponentRequirement::SOFT); // Optional component
86
87 bool success = false;
88 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
89
90 RCLCPP_INFO_STREAM(
91 getLogger(), "[CbMoveEndEffector] Target End effector Pose: " << targetObjectPose);
92
93 if (motionPlanner != nullptr)
94 {
95 // Use component-based motion planner (preferred)
96 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] Using CpMotionPlanner component for planning");
97
98 PlanningOptions options;
99 options.planningTime = 1.0;
100 options.poseReferenceFrame = targetObjectPose.header.frame_id;
101
102 std::optional<std::string> tipLinkOpt;
103 if (!tip_link_.empty())
104 {
105 tipLinkOpt = tip_link_;
106 }
107
108 auto result = motionPlanner->planToPose(targetObjectPose, tipLinkOpt, options);
109
110 success = result.success;
111 if (success)
112 {
113 computedMotionPlan = result.plan;
114 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] Planning succeeded (via CpMotionPlanner)");
115 }
116 else
117 {
118 RCLCPP_WARN(
119 getLogger(), "[CbMoveEndEffector] Planning failed (via CpMotionPlanner): %s",
120 result.errorMessage.c_str());
121 }
122 }
123 else
124 {
125 // Fallback to legacy direct API calls
126 RCLCPP_WARN(
127 getLogger(),
128 "[CbMoveEndEffector] CpMotionPlanner component not available, using legacy planning "
129 "(consider adding CpMotionPlanner component)");
130
131 moveGroupInterface.setPlanningTime(1.0);
132 moveGroupInterface.setPoseTarget(targetObjectPose, tip_link_);
133 moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);
134
135 success =
136 (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
137 RCLCPP_INFO(
138 getLogger(), "[CbMoveEndEffector] Planning %s (legacy mode)",
139 success ? "succeeded" : "FAILED");
140 }
141
142 // Execution
143 if (success)
144 {
145 // Try to use CpTrajectoryExecutor component (preferred)
146 CpTrajectoryExecutor * trajectoryExecutor = nullptr;
147 this->requiresComponent(
148 trajectoryExecutor, smacc2::ComponentRequirement::SOFT); // Optional component
149
150 bool executionSuccess = false;
151
152 if (trajectoryExecutor != nullptr)
153 {
154 // Use component-based trajectory executor (preferred)
155 RCLCPP_INFO(
156 getLogger(), "[CbMoveEndEffector] Using CpTrajectoryExecutor component for execution");
157
158 ExecutionOptions execOptions;
159 execOptions.trajectoryName = this->getName();
160
161 auto execResult = trajectoryExecutor->executePlan(computedMotionPlan, execOptions);
162 executionSuccess = execResult.success;
163
164 if (executionSuccess)
165 {
166 RCLCPP_INFO(
167 getLogger(), "[CbMoveEndEffector] Execution succeeded (via CpTrajectoryExecutor)");
168 }
169 else
170 {
171 RCLCPP_WARN(
172 getLogger(), "[CbMoveEndEffector] Execution failed (via CpTrajectoryExecutor): %s",
173 execResult.errorMessage.c_str());
174 }
175 }
176 else
177 {
178 // Fallback to legacy direct execution
179 RCLCPP_WARN(
180 getLogger(),
181 "[CbMoveEndEffector] CpTrajectoryExecutor component not available, using legacy "
182 "execution "
183 "(consider adding CpTrajectoryExecutor component)");
184
185 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
186 executionSuccess = (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
187
188 RCLCPP_INFO(
189 getLogger(), "[CbMoveEndEffector] Execution %s (legacy mode)",
190 executionSuccess ? "succeeded" : "failed");
191 }
192
193 // Post events
194 if (executionSuccess)
195 {
197 this->postSuccessEvent();
198 }
199 else
200 {
202 this->postFailureEvent();
203 }
204 }
205 else
206 {
207 RCLCPP_INFO(getLogger(), "[CbMoveEndEffector] planning failed, skipping execution");
209 this->postFailureEvent();
210 }
211
212 RCLCPP_DEBUG(getLogger(), "[CbMoveEndEffector] Synchronous sleep of 1 seconds");
213 rclcpp::sleep_for(500ms);
214
215 return success;
216 }
217
219};
220} // namespace cl_moveit2z
bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::msg::PoseStamped &targetObjectPose)
std::optional< std::string > group_
CbMoveEndEffector(geometry_msgs::msg::PoseStamped target_pose, std::string tip_link="")
geometry_msgs::msg::PoseStamped targetPose
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
Component for centralized motion planning operations.
PlanningResult planToPose(const geometry_msgs::msg::PoseStamped &target, const std::optional< std::string > &tipLink=std::nullopt, const PlanningOptions &options={})
Plan to a Cartesian pose.
Component for centralized trajectory execution.
ExecutionResult executePlan(const moveit::planning_interface::MoveGroupInterface::Plan &plan, const ExecutionOptions &options={})
Execute a motion plan synchronously.
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
Configuration options for trajectory execution.
std::optional< std::string > trajectoryName
Configuration options for motion planning.
std::optional< std::string > poseReferenceFrame
std::optional< double > planningTime