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

#include <cb_move_joints.hpp>

Inheritance diagram for cl_moveit2z::CbMoveJoints:
Inheritance graph
Collaboration diagram for cl_moveit2z::CbMoveJoints:
Collaboration graph

Public Member Functions

 CbMoveJoints ()
 
 CbMoveJoints (const std::map< std::string, double > &jointValueTarget)
 
virtual void onEntry () override
 
virtual void onExit () 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)
 

Public Attributes

std::optional< double > scalingFactor_
 
std::map< std::string, double > jointValueTarget_
 
std::optional< std::string > group_
 

Protected Member Functions

void moveJoints (moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
 
- 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
 

Static Protected Member Functions

static std::string currentJointStatesToString (moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)
 

Protected Attributes

ClMoveit2zmovegroupClient_
 

Detailed Description

Definition at line 36 of file cb_move_joints.hpp.

Constructor & Destructor Documentation

◆ CbMoveJoints() [1/2]

cl_moveit2z::CbMoveJoints::CbMoveJoints ( )
inline

Definition at line 43 of file cb_move_joints.hpp.

43{}

◆ CbMoveJoints() [2/2]

cl_moveit2z::CbMoveJoints::CbMoveJoints ( const std::map< std::string, double > & jointValueTarget)
inline

Definition at line 45 of file cb_move_joints.hpp.

46 : jointValueTarget_(jointValueTarget)
47 {
48 }
std::map< std::string, double > jointValueTarget_

Member Function Documentation

◆ currentJointStatesToString()

static std::string cl_moveit2z::CbMoveJoints::currentJointStatesToString ( moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
std::map< std::string, double > & targetJoints )
inlinestaticprotected

Definition at line 69 of file cb_move_joints.hpp.

72 {
73 auto state = moveGroupInterface.getCurrentState();
74
75 if (state == nullptr) return std::string();
76
77 auto vnames = state->getVariableNames();
78
79 std::stringstream ss;
80
81 for (auto & tgj : targetJoints)
82 {
83 auto it = std::find(vnames.begin(), vnames.end(), tgj.first);
84 auto index = std::distance(vnames.begin(), it);
85
86 ss << tgj.first << ":" << state->getVariablePosition(index) << std::endl;
87 }
88
89 return ss.str();
90 }

Referenced by moveJoints().

Here is the caller graph for this function:

◆ moveJoints()

void cl_moveit2z::CbMoveJoints::moveJoints ( moveit::planning_interface::MoveGroupInterface & moveGroupInterface)
inlineprotected

Definition at line 92 of file cb_move_joints.hpp.

93 {
94 if (jointValueTarget_.size() == 0)
95 {
96 RCLCPP_WARN(getLogger(), "[CbMoveJoints] No joint value specified. Skipping planning call.");
98 this->postFailureEvent();
99 return;
100 }
101
102 // Try to use CpMotionPlanner component (preferred)
103 CpMotionPlanner * motionPlanner = nullptr;
104 this->requiresComponent(
105 motionPlanner, smacc2::ComponentRequirement::SOFT); // Optional component
106
107 bool success = false;
108 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
109
110 if (motionPlanner != nullptr)
111 {
112 // Use component-based motion planner (preferred)
113 RCLCPP_INFO(getLogger(), "[CbMoveJoints] Using CpMotionPlanner component for joint planning");
114
115 PlanningOptions options;
116 if (scalingFactor_)
117 {
118 options.maxVelocityScaling = *scalingFactor_;
119 }
120
121 auto result = motionPlanner->planToJointTarget(jointValueTarget_, options);
122
123 success = result.success;
124 if (success)
125 {
126 computedMotionPlan = result.plan;
127 RCLCPP_INFO(getLogger(), "[CbMoveJoints] Planning succeeded (via CpMotionPlanner)");
128 }
129 else
130 {
131 RCLCPP_WARN(
132 getLogger(), "[CbMoveJoints] Planning failed (via CpMotionPlanner): %s",
133 result.errorMessage.c_str());
134 }
135 }
136 else
137 {
138 // Fallback to legacy direct API calls
139 RCLCPP_WARN(
140 getLogger(),
141 "[CbMoveJoints] CpMotionPlanner component not available, using legacy planning "
142 "(consider adding CpMotionPlanner component)");
143
144 if (scalingFactor_) moveGroupInterface.setMaxVelocityScalingFactor(*scalingFactor_);
145
146 moveGroupInterface.setJointValueTarget(jointValueTarget_);
147
148 auto result = moveGroupInterface.plan(computedMotionPlan);
149
150 success = (result == moveit::core::MoveItErrorCode::SUCCESS);
151
152 RCLCPP_INFO(
153 getLogger(), "[CbMoveJoints] Planning %s (legacy mode, code: %d)",
154 success ? "SUCCESS" : "FAILED", result.val);
155 }
156
157 // Execution
158 if (success)
159 {
160 // Try to use CpTrajectoryExecutor component (preferred)
161 CpTrajectoryExecutor * trajectoryExecutor = nullptr;
162 this->requiresComponent(
163 trajectoryExecutor, smacc2::ComponentRequirement::SOFT); // Optional component
164
165 bool executionSuccess = false;
166
167 if (trajectoryExecutor != nullptr)
168 {
169 // Use component-based trajectory executor (preferred)
170 RCLCPP_INFO(
171 getLogger(), "[CbMoveJoints] Using CpTrajectoryExecutor component for execution");
172
173 ExecutionOptions execOptions;
174 execOptions.trajectoryName = this->getName();
175 if (scalingFactor_)
176 {
177 execOptions.maxVelocityScaling = *scalingFactor_;
178 }
179
180 auto execResult = trajectoryExecutor->executePlan(computedMotionPlan, execOptions);
181 executionSuccess = execResult.success;
182
183 if (executionSuccess)
184 {
185 RCLCPP_INFO(getLogger(), "[CbMoveJoints] Execution succeeded (via CpTrajectoryExecutor)");
186 }
187 else
188 {
189 RCLCPP_WARN(
190 getLogger(), "[CbMoveJoints] Execution failed (via CpTrajectoryExecutor): %s",
191 execResult.errorMessage.c_str());
192 }
193 }
194 else
195 {
196 // Fallback to legacy direct execution
197 RCLCPP_WARN(
198 getLogger(),
199 "[CbMoveJoints] CpTrajectoryExecutor component not available, using legacy execution "
200 "(consider adding CpTrajectoryExecutor component)");
201
202 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
203 executionSuccess = (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
204
205 RCLCPP_INFO(
206 getLogger(), "[CbMoveJoints] Execution %s (legacy mode)",
207 executionSuccess ? "succeeded" : "failed");
208 }
209
210 // Post events
211 if (executionSuccess)
212 {
213 RCLCPP_INFO_STREAM(
214 getLogger(),
215 "[" << this->getName() << "] motion execution succeeded. Throwing success event.");
217 this->postSuccessEvent();
218 }
219 else
220 {
221 RCLCPP_WARN_STREAM(
222 getLogger(), "[" << this->getName() << "] motion execution failed. Throwing fail event.");
224 this->postFailureEvent();
225 }
226 }
227 else
228 {
229 auto statestr = currentJointStatesToString(moveGroupInterface, jointValueTarget_);
230 RCLCPP_WARN_STREAM(
231 getLogger(), "[" << this->getName() << "] planning failed. Throwing fail event."
232 << std::endl
233 << statestr);
235 this->postFailureEvent();
236 }
237 }
static std::string currentJointStatesToString(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)
std::optional< double > scalingFactor_
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)

References currentJointStatesToString(), cl_moveit2z::CpTrajectoryExecutor::executePlan(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), jointValueTarget_, cl_moveit2z::ExecutionOptions::maxVelocityScaling, cl_moveit2z::PlanningOptions::maxVelocityScaling, movegroupClient_, cl_moveit2z::CpMotionPlanner::planToJointTarget(), cl_moveit2z::ClMoveit2z::postEventMotionExecutionFailed(), cl_moveit2z::ClMoveit2z::postEventMotionExecutionSucceded(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), smacc2::ISmaccClientBehavior::requiresComponent(), scalingFactor_, smacc2::SOFT, 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::CbMoveJoints::onEntry ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Reimplemented in cl_moveit2z::CbMoveKnownState.

Definition at line 50 of file cb_move_joints.hpp.

51 {
53
54 if (this->group_)
55 {
56 moveit::planning_interface::MoveGroupInterface move_group(
57 getNode(), moveit::planning_interface::MoveGroupInterface::Options(*(this->group_)));
58 this->moveJoints(move_group);
59 }
60 else
61 {
63 }
64 }
void moveJoints(moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
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::getNode(), movegroupClient_, cl_moveit2z::ClMoveit2z::moveGroupClientInterface, moveJoints(), and smacc2::ISmaccClientBehavior::requiresClient().

Referenced by cl_moveit2z::CbMoveKnownState::onEntry().

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

◆ onExit()

virtual void cl_moveit2z::CbMoveJoints::onExit ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 66 of file cb_move_joints.hpp.

66{}

Member Data Documentation

◆ group_

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

Definition at line 41 of file cb_move_joints.hpp.

◆ jointValueTarget_

std::map<std::string, double> cl_moveit2z::CbMoveJoints::jointValueTarget_

Definition at line 40 of file cb_move_joints.hpp.

Referenced by moveJoints(), and cl_moveit2z::CbMoveKnownState::onEntry().

◆ movegroupClient_

ClMoveit2z* cl_moveit2z::CbMoveJoints::movegroupClient_
protected

Definition at line 239 of file cb_move_joints.hpp.

Referenced by moveJoints(), and onEntry().

◆ scalingFactor_

std::optional<double> cl_moveit2z::CbMoveJoints::scalingFactor_

Definition at line 39 of file cb_move_joints.hpp.

Referenced by moveJoints().


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