SMACC2
Loading...
Searching...
No Matches
cl_moveit2z::CbMoveEndEffector Class Reference

#include <cb_move_end_effector.hpp>

Inheritance diagram for cl_moveit2z::CbMoveEndEffector:
Inheritance graph
Collaboration diagram for cl_moveit2z::CbMoveEndEffector:
Collaboration graph

Public Member Functions

 CbMoveEndEffector ()
 
 CbMoveEndEffector (geometry_msgs::msg::PoseStamped target_pose, std::string tip_link="")
 
virtual void onEntry () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
virtual void onExit ()
 

Public Attributes

geometry_msgs::msg::PoseStamped targetPose
 
std::string tip_link_
 
std::optional< std::string > group_
 

Protected Member Functions

bool moveToAbsolutePose (moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::msg::PoseStamped &targetObjectPose)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Protected Attributes

ClMoveit2zmovegroupClient_
 

Detailed Description

Definition at line 36 of file cb_move_end_effector.hpp.

Constructor & Destructor Documentation

◆ CbMoveEndEffector() [1/2]

cl_moveit2z::CbMoveEndEffector::CbMoveEndEffector ( )
inline

Definition at line 43 of file cb_move_end_effector.hpp.

43{}

◆ CbMoveEndEffector() [2/2]

cl_moveit2z::CbMoveEndEffector::CbMoveEndEffector ( geometry_msgs::msg::PoseStamped target_pose,
std::string tip_link = "" )
inline

Definition at line 45 of file cb_move_end_effector.hpp.

46 : targetPose(target_pose)
47 {
48 tip_link_ = tip_link;
49 }
geometry_msgs::msg::PoseStamped targetPose

References tip_link_.

Member Function Documentation

◆ moveToAbsolutePose()

bool cl_moveit2z::CbMoveEndEffector::moveToAbsolutePose ( moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
geometry_msgs::msg::PoseStamped & targetObjectPose )
inlineprotected

Definition at line 75 of file cb_move_end_effector.hpp.

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 }
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)

References cl_moveit2z::CpTrajectoryExecutor::executePlan(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), movegroupClient_, cl_moveit2z::PlanningOptions::planningTime, cl_moveit2z::CpMotionPlanner::planToPose(), cl_moveit2z::PlanningOptions::poseReferenceFrame, cl_moveit2z::ClMoveit2z::postEventMotionExecutionFailed(), cl_moveit2z::ClMoveit2z::postEventMotionExecutionSucceded(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), smacc2::ISmaccClientBehavior::requiresComponent(), smacc2::SOFT, tip_link_, and cl_moveit2z::ExecutionOptions::trajectoryName.

Referenced by onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onEntry()

virtual void cl_moveit2z::CbMoveEndEffector::onEntry ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 51 of file cb_move_end_effector.hpp.

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 }
bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::msg::PoseStamped &targetObjectPose)
std::optional< std::string > group_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)

References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), group_, movegroupClient_, cl_moveit2z::ClMoveit2z::moveGroupClientInterface, moveToAbsolutePose(), smacc2::ISmaccClientBehavior::requiresClient(), and targetPose.

Here is the call graph for this function:

Member Data Documentation

◆ group_

std::optional<std::string> cl_moveit2z::CbMoveEndEffector::group_

Definition at line 41 of file cb_move_end_effector.hpp.

Referenced by onEntry().

◆ movegroupClient_

ClMoveit2z* cl_moveit2z::CbMoveEndEffector::movegroupClient_
protected

Definition at line 218 of file cb_move_end_effector.hpp.

Referenced by moveToAbsolutePose(), and onEntry().

◆ targetPose

geometry_msgs::msg::PoseStamped cl_moveit2z::CbMoveEndEffector::targetPose

Definition at line 39 of file cb_move_end_effector.hpp.

Referenced by onEntry().

◆ tip_link_

std::string cl_moveit2z::CbMoveEndEffector::tip_link_

Definition at line 40 of file cb_move_end_effector.hpp.

Referenced by CbMoveEndEffector(), and moveToAbsolutePose().


The documentation for this class was generated from the following file: