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
 
 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 onOrthogonalAllocation ()
 
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, bool throwExceptionIfNotExist)
 
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)
 
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 31 of file cb_move_joints.hpp.

Constructor & Destructor Documentation

◆ CbMoveJoints() [1/4]

cl_moveit2z::CbMoveJoints::CbMoveJoints ( )
inline

Definition at line 43 of file cb_move_joints.hpp.

43{}

◆ CbMoveJoints() [2/4]

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_

◆ CbMoveJoints() [3/4]

cl_moveit2z::CbMoveJoints::CbMoveJoints ( )

◆ CbMoveJoints() [4/4]

cl_moveit2z::CbMoveJoints::CbMoveJoints ( const 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() [1/2]

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

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_, and cl_moveit2z::ExecutionOptions::trajectoryName.

Referenced by onEntry().

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

◆ moveJoints() [2/2]

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

◆ onEntry() [1/2]

void cl_moveit2z::CbMoveJoints::onEntry ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Reimplemented in cl_moveit2z::CbMoveKnownState, cl_moveit2z::CbMoveKnownState, and cl_moveit2z::CbMoveLastTrajectoryInitialState.

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(), and cl_moveit2z::CbMoveLastTrajectoryInitialState::onEntry().

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

◆ onEntry() [2/2]

virtual void cl_moveit2z::CbMoveJoints::onEntry ( )
overridevirtual

◆ onExit() [1/2]

void cl_moveit2z::CbMoveJoints::onExit ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 66 of file cb_move_joints.hpp.

66{}

◆ onExit() [2/2]

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

Reimplemented from smacc2::ISmaccClientBehavior.

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_

◆ movegroupClient_

ClMoveit2z * cl_moveit2z::CbMoveJoints::movegroupClient_
protected

Definition at line 237 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 files: