SMACC2
Loading...
Searching...
No Matches
cb_move_end_effector_trajectory.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/transform_datatypes.h>
24#include <tf2_ros/transform_listener.h>
32#include <moveit_msgs/srv/get_position_ik.hpp>
34#include <visualization_msgs/msg/marker_array.hpp>
35
36using namespace std::chrono_literals;
37
38namespace cl_moveit2z
39{
40template <typename AsyncCB, typename Orthogonal>
41struct EvJointDiscontinuity : sc::event<EvJointDiscontinuity<AsyncCB, Orthogonal>>
42{
43 moveit_msgs::msg::RobotTrajectory trajectory;
44};
45
46template <typename AsyncCB, typename Orthogonal>
47struct EvIncorrectInitialPosition : sc::event<EvIncorrectInitialPosition<AsyncCB, Orthogonal>>
48{
49 moveit_msgs::msg::RobotTrajectory trajectory;
50};
51
58
59// this is a base behavior to define any kind of parameterized family of trajectories or motions
61{
62public:
63 // std::string tip_link_;
64 std::optional<std::string> group_;
65
66 std::optional<std::string> tipLink_;
67
69
70 CbMoveEndEffectorTrajectory(std::optional<std::string> tipLink = std::nullopt) : tipLink_(tipLink)
71 {
72 }
73
75 const std::vector<geometry_msgs::msg::PoseStamped> & endEffectorTrajectory,
76 std::optional<std::string> tipLink = std::nullopt)
77 : tipLink_(tipLink), endEffectorTrajectory_(endEffectorTrajectory)
78 {
79 }
80
81 template <typename TOrthogonal, typename TSourceObject>
83 {
84 this->initializeROS();
85
87
88 postJointDiscontinuityEvent = [this](auto traj)
89 {
91 ev->trajectory = traj;
92 this->postEvent(ev);
93 };
94
95 postIncorrectInitialStateEvent = [this](auto traj)
96 {
98 ev->trajectory = traj;
99 this->postEvent(ev);
100 };
101
103 {
104 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] motion execution failed");
107 };
108 }
109
110 virtual void onEntry() override
111 {
113
114 // Get optional components for visualization
115 CpTrajectoryVisualizer * trajectoryVisualizer = nullptr;
116 this->requiresComponent(
117 trajectoryVisualizer, smacc2::ComponentRequirement::SOFT); // Optional component
118
119 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Generating end effector trajectory");
120
121 this->generateTrajectory();
122
123 if (this->endEffectorTrajectory_.size() == 0)
124 {
125 RCLCPP_WARN_STREAM(
126 getLogger(), "[" << smacc2::demangleSymbol(typeid(*this).name())
127 << "] No points in the trajectory. Skipping behavior.");
128 return;
129 }
130
131 // Use CpTrajectoryVisualizer if available, otherwise use legacy marker system
132 if (trajectoryVisualizer != nullptr)
133 {
134 RCLCPP_INFO_STREAM(
135 getLogger(),
136 "[" << getName() << "] Setting trajectory visualization using CpTrajectoryVisualizer.");
137 trajectoryVisualizer->setTrajectory(this->endEffectorTrajectory_, "trajectory");
138 }
139 else
140 {
141 RCLCPP_INFO_STREAM(
142 getLogger(), "[" << getName()
143 << "] Creating markers (legacy mode - consider adding "
144 "CpTrajectoryVisualizer component).");
145 this->createMarkers();
146 }
147
148 moveit_msgs::msg::RobotTrajectory computedTrajectory;
149
150 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Computing joint space trajectory.");
151
152 auto errorcode = computeJointSpaceTrajectory(computedTrajectory);
153
154 bool trajectoryGenerationSuccess = errorcode == ComputeJointTrajectoryErrorCode::SUCCESS;
155
156 CpTrajectoryHistory * trajectoryHistory;
157 this->requiresComponent(trajectoryHistory);
158
159 if (!trajectoryGenerationSuccess)
160 {
161 RCLCPP_INFO_STREAM(
162 getLogger(), "[" << this->getName() << "] Incorrect trajectory. Posting failure event.");
163 if (trajectoryHistory != nullptr)
164 {
165 moveit_msgs::msg::MoveItErrorCodes error;
166 error.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
167 trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);
168 }
169
171 this->postFailureEvent();
172
174 {
175 this->postJointDiscontinuityEvent(computedTrajectory);
176 }
178 {
179 this->postIncorrectInitialStateEvent(computedTrajectory);
180 }
181 return;
182 }
183 else
184 {
185 if (trajectoryHistory != nullptr)
186 {
187 moveit_msgs::msg::MoveItErrorCodes error;
188 error.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
189 trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);
190 }
191
192 this->executeJointSpaceTrajectory(computedTrajectory);
193 }
194
195 // handle finishing events
196 }
197
198 // onExit removed - requiresComponent() during state disposal causes deadlock
199 // Components and markers are automatically cleaned up when state is destroyed
200 // If manual cleanup needed in future, use empty onExit like CbMoveJoints
201 virtual void onExit() override {}
202
203protected:
205 moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
206 {
207 // Try to use CpJointSpaceTrajectoryPlanner component (preferred)
208 CpJointSpaceTrajectoryPlanner * trajectoryPlanner = nullptr;
209 this->requiresComponent(
210 trajectoryPlanner, smacc2::ComponentRequirement::SOFT); // Optional component
211
212 if (trajectoryPlanner != nullptr)
213 {
214 // Use component-based trajectory planner (preferred)
215 RCLCPP_INFO(
216 getLogger(),
217 "[CbMoveEndEffectorTrajectory] Using CpJointSpaceTrajectoryPlanner component for IK "
218 "trajectory generation");
219
221 if (tipLink_ && !tipLink_->empty())
222 {
223 options.tipLink = *tipLink_;
224 }
226 {
228 }
229
230 auto result = trajectoryPlanner->planFromWaypoints(endEffectorTrajectory_, options);
231
232 if (result.success)
233 {
234 computedJointTrajectory = result.trajectory;
235 RCLCPP_INFO(
236 getLogger(),
237 "[CbMoveEndEffectorTrajectory] IK trajectory generation succeeded (via "
238 "CpJointSpaceTrajectoryPlanner)");
240 }
241 else
242 {
243 computedJointTrajectory = result.trajectory; // Still return partial trajectory
244 RCLCPP_WARN(
245 getLogger(),
246 "[CbMoveEndEffectorTrajectory] IK trajectory generation failed (via "
247 "CpJointSpaceTrajectoryPlanner): %s",
248 result.errorMessage.c_str());
249
250 // Map error codes
251 switch (result.errorCode)
252 {
257 default:
259 }
260 }
261 }
262 else
263 {
264 // Fallback to legacy IK trajectory generation
265 RCLCPP_WARN(
266 getLogger(),
267 "[CbMoveEndEffectorTrajectory] CpJointSpaceTrajectoryPlanner component not available, "
268 "using legacy IK trajectory generation (consider adding CpJointSpaceTrajectoryPlanner "
269 "component)");
270
271 // LEGACY IMPLEMENTATION (keep for backward compatibility)
272 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting current state.. waiting");
273
274 auto currentState = movegroupClient_->moveGroupClientInterface->getCurrentState(100);
275 auto groupname = movegroupClient_->moveGroupClientInterface->getName();
276
277 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting joint names");
278 auto currentjointnames =
279 currentState->getJointModelGroup(groupname)->getActiveJointModelNames();
280
281 if (!tipLink_ || *tipLink_ == "")
282 {
283 tipLink_ = movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
284 }
285
286 std::vector<double> jointPositions;
287 currentState->copyJointGroupPositions(groupname, jointPositions);
288
289 std::vector<std::vector<double>> trajectory;
290 std::vector<rclcpp::Duration> trajectoryTimeStamps;
291
292 trajectory.push_back(jointPositions);
293 trajectoryTimeStamps.push_back(rclcpp::Duration(0s));
294
295 auto & first = endEffectorTrajectory_.front();
296 rclcpp::Time referenceTime(first.header.stamp);
297
298 std::vector<int> discontinuityIndexes;
299
300 int ikAttempts = 4;
301 for (size_t k = 0; k < this->endEffectorTrajectory_.size(); k++)
302 {
303 auto & pose = this->endEffectorTrajectory_[k];
304 auto req = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
305
306 req->ik_request.ik_link_name = *tipLink_;
307 req->ik_request.robot_state.joint_state.name = currentjointnames;
308 req->ik_request.robot_state.joint_state.position = jointPositions;
309 req->ik_request.group_name = groupname;
310 req->ik_request.avoid_collisions = true;
311 req->ik_request.pose_stamped = pose;
312
313 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] IK request: " << k << " " << *req);
314
315 auto resfut = iksrv_->async_send_request(req);
316 auto status = resfut.wait_for(3s);
317
318 if (status == std::future_status::ready)
319 {
320 auto & prevtrajpoint = trajectory.back();
321 auto res = resfut.get();
322
323 std::stringstream ss;
324 for (size_t j = 0; j < res->solution.joint_state.position.size(); j++)
325 {
326 auto & jointname = res->solution.joint_state.name[j];
327 auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);
328 if (it != currentjointnames.end())
329 {
330 int index = std::distance(currentjointnames.begin(), it);
331 jointPositions[index] = res->solution.joint_state.position[j];
332 ss << jointname << "(" << index << "): " << jointPositions[index] << std::endl;
333 }
334 }
335
336 // Continuity check
337 size_t jointindex = 0;
338 int discontinuityJointIndex = -1;
339 double discontinuityDeltaJointIndex = -1;
340 double deltajoint;
341
342 bool check = k > 0 || !allowInitialTrajectoryStateJointDiscontinuity_ ||
344 !(*allowInitialTrajectoryStateJointDiscontinuity_));
345 if (check)
346 {
347 for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)
348 {
349 deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];
350 if (fabs(deltajoint) > 0.3)
351 {
352 discontinuityDeltaJointIndex = deltajoint;
353 discontinuityJointIndex = jointindex;
354 }
355 }
356 }
357
358 if (ikAttempts > 0 && discontinuityJointIndex != -1)
359 {
360 k--;
361 ikAttempts--;
362 continue;
363 }
364 else
365 {
366 bool discontinuity = false;
367 if (ikAttempts == 0)
368 {
369 discontinuityIndexes.push_back(k);
370 discontinuity = true;
371 }
372
373 ikAttempts = 4;
374
375 if (discontinuity && discontinuityJointIndex != -1)
376 {
377 std::stringstream ss;
378 ss << "Traj[" << k << "/" << endEffectorTrajectory_.size() << "] "
379 << currentjointnames[discontinuityJointIndex]
380 << " IK discontinuity : " << discontinuityDeltaJointIndex << std::endl
381 << "prev joint value: " << prevtrajpoint[discontinuityJointIndex] << std::endl
382 << "current joint value: " << jointPositions[discontinuityJointIndex] << std::endl;
383
384 ss << std::endl;
385 for (size_t ji = 0; ji < jointPositions.size(); ji++)
386 {
387 ss << currentjointnames[ji] << ": " << jointPositions[ji] << std::endl;
388 }
389
390 for (size_t kindex = 0; kindex < trajectory.size(); kindex++)
391 {
392 ss << "[" << kindex << "]: " << trajectory[kindex][discontinuityJointIndex]
393 << std::endl;
394 }
395
396 if (k == 0)
397 {
398 ss
399 << "This is the first posture of the trajectory. Maybe the robot initial posture "
400 "is "
401 "not coincident to the initial posture of the generated joint trajectory."
402 << std::endl;
403 }
404
405 RCLCPP_ERROR_STREAM(getLogger(), ss.str());
406
407 trajectory.push_back(jointPositions);
408 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
409 trajectoryTimeStamps.push_back(durationFromStart);
410 continue;
411 }
412 else
413 {
414 trajectory.push_back(jointPositions);
415 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
416 trajectoryTimeStamps.push_back(durationFromStart);
417
418 RCLCPP_DEBUG_STREAM(getLogger(), "IK solution: " << res->solution.joint_state);
419 RCLCPP_DEBUG_STREAM(getLogger(), "trajpoint: " << std::endl << ss.str());
420 }
421 }
422 }
423 else
424 {
425 RCLCPP_ERROR_STREAM(getLogger(), "[" << getName() << "] wrong IK call");
426 }
427 }
428
429 computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;
430 int i = 0;
431 for (auto & p : trajectory)
432 {
433 if (i == 0) // Skip current state
434 {
435 i++;
436 continue;
437 }
438
439 trajectory_msgs::msg::JointTrajectoryPoint jp;
440 jp.positions = p;
441 jp.time_from_start = trajectoryTimeStamps[i];
442 computedJointTrajectory.joint_trajectory.points.push_back(jp);
443 i++;
444 }
445
446 if (discontinuityIndexes.size())
447 {
448 if (discontinuityIndexes[0] == 0)
450 else
452 }
453
455 }
456 }
457
459 const moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
460 {
461 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Executing joint trajectory");
462
463 // Try to use CpTrajectoryExecutor component (preferred)
464 CpTrajectoryExecutor * trajectoryExecutor = nullptr;
465 this->requiresComponent(
466 trajectoryExecutor, smacc2::ComponentRequirement::SOFT); // Optional component
467
468 bool executionSuccess = false;
469
470 if (trajectoryExecutor != nullptr)
471 {
472 // Use component-based trajectory executor (preferred)
473 RCLCPP_INFO(
474 getLogger(),
475 "[CbMoveEndEffectorTrajectory] Using CpTrajectoryExecutor component for execution");
476
477 ExecutionOptions execOptions;
478 execOptions.trajectoryName = this->getName();
479
480 auto execResult = trajectoryExecutor->execute(computedJointTrajectory, execOptions);
481 executionSuccess = execResult.success;
482
483 if (executionSuccess)
484 {
485 RCLCPP_INFO(
486 getLogger(),
487 "[CbMoveEndEffectorTrajectory] Execution succeeded (via CpTrajectoryExecutor)");
488 }
489 else
490 {
491 RCLCPP_WARN(
492 getLogger(),
493 "[CbMoveEndEffectorTrajectory] Execution failed (via CpTrajectoryExecutor): %s",
494 execResult.errorMessage.c_str());
495 }
496 }
497 else
498 {
499 // Fallback to legacy direct execution
500 RCLCPP_WARN(
501 getLogger(),
502 "[CbMoveEndEffectorTrajectory] CpTrajectoryExecutor component not available, using legacy "
503 "execution (consider adding CpTrajectoryExecutor component)");
504
505 auto executionResult =
506 this->movegroupClient_->moveGroupClientInterface->execute(computedJointTrajectory);
507 executionSuccess = (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
508
509 RCLCPP_INFO(
510 getLogger(), "[CbMoveEndEffectorTrajectory] Execution %s (legacy mode)",
511 executionSuccess ? "succeeded" : "failed");
512 }
513
514 // Post events
515 if (executionSuccess)
516 {
517 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] motion execution succeeded");
519 this->postSuccessEvent();
520 }
521 else
522 {
524 this->postFailureEvent();
525 }
526 }
527
528 virtual void generateTrajectory()
529 {
530 // bypass current trajectory, overridden in derived classes
531 // this->endEffectorTrajectory_ = ...
532 }
533
534 virtual void createMarkers()
535 {
536 tf2::Transform localdirection;
537 localdirection.setIdentity();
538 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
539 auto frameid = this->endEffectorTrajectory_.front().header.frame_id;
540
541 for (auto & pose : this->endEffectorTrajectory_)
542 {
543 visualization_msgs::msg::Marker marker;
544 marker.header.frame_id = frameid;
545 marker.header.stamp = getNode()->now();
546 marker.ns = "trajectory";
547 marker.id = this->beahiorMarkers_.markers.size();
548 marker.type = visualization_msgs::msg::Marker::ARROW;
549 marker.action = visualization_msgs::msg::Marker::ADD;
550 marker.scale.x = 0.005;
551 marker.scale.y = 0.01;
552 marker.scale.z = 0.01;
553 marker.color.a = 0.8;
554 marker.color.r = 1.0;
555 marker.color.g = 0;
556 marker.color.b = 0;
557
558 geometry_msgs::msg::Point start, end;
559 start.x = 0;
560 start.y = 0;
561 start.z = 0;
562
563 tf2::Transform basetransform;
564 tf2::fromMsg(pose.pose, basetransform);
565 // tf2::Transform endarrow = localdirection * basetransform;
566
567 end.x = localdirection.getOrigin().x();
568 end.y = localdirection.getOrigin().y();
569 end.z = localdirection.getOrigin().z();
570
571 marker.pose.position = pose.pose.position;
572 marker.pose.orientation = pose.pose.orientation;
573 marker.points.push_back(start);
574 marker.points.push_back(end);
575
576 beahiorMarkers_.markers.push_back(marker);
577 }
578 }
579
580 std::vector<geometry_msgs::msg::PoseStamped> endEffectorTrajectory_;
581
583
584 visualization_msgs::msg::MarkerArray beahiorMarkers_;
585
587 std::string globalFrame, tf2::Stamped<tf2::Transform> & currentEndEffectorTransform)
588 {
589 // Use CpTfListener component for transform lookups
590 CpTfListener * tfListener = nullptr;
591 this->requiresComponent(tfListener, smacc2::ComponentRequirement::SOFT); // Optional component
592
593 try
594 {
595 if (!tipLink_ || *tipLink_ == "")
596 {
597 tipLink_ = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
598 }
599
600 if (tfListener != nullptr)
601 {
602 // Use component-based TF listener (preferred)
603 auto transformOpt = tfListener->lookupTransform(globalFrame, *tipLink_, rclcpp::Time(0));
604 if (transformOpt)
605 {
606 tf2::fromMsg(transformOpt.value(), currentEndEffectorTransform);
607 }
608 else
609 {
610 RCLCPP_ERROR_STREAM(
611 getLogger(), "[" << getName() << "] Failed to lookup transform from " << *tipLink_
612 << " to " << globalFrame);
613 }
614 }
615 else
616 {
617 // Fallback to legacy TF2 usage if component not available
618 RCLCPP_WARN_STREAM(
619 getLogger(), "[" << getName()
620 << "] CpTfListener component not available, using legacy TF2 (consider "
621 "adding CpTfListener component)");
622 tf2_ros::Buffer tfBuffer(getNode()->get_clock());
623 tf2_ros::TransformListener tfListenerLegacy(tfBuffer);
624
625 tf2::fromMsg(
626 tfBuffer.lookupTransform(globalFrame, *tipLink_, rclcpp::Time(0), rclcpp::Duration(10s)),
627 currentEndEffectorTransform);
628 }
629 }
630 catch (const std::exception & e)
631 {
632 RCLCPP_ERROR_STREAM(
633 getLogger(), "[" << getName() << "] Exception in getCurrentEndEffectorPose: " << e.what());
634 }
635 }
636
637private:
639 {
640 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] initializing ros");
641
642 auto nh = this->getNode();
643
644 // Only create marker publisher for legacy mode (when CpTrajectoryVisualizer is not used)
645 markersPub_ = nh->create_publisher<visualization_msgs::msg::MarkerArray>(
646 "trajectory_markers", rclcpp::QoS(1));
647
648 iksrv_ = nh->create_client<moveit_msgs::srv::GetPositionIK>("/compute_ik");
649 }
650
651 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr markersPub_;
652
653 rclcpp::Client<moveit_msgs::srv::GetPositionIK>::SharedPtr iksrv_;
654
655 std::mutex m_mutex_;
656
657 std::function<void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent;
658 std::function<void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent;
659
660 std::function<void()> postMotionExecutionFailureEvents;
661
662 bool autocleanmarkers = false;
663};
664} // namespace cl_moveit2z
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
CbMoveEndEffectorTrajectory(std::optional< std::string > tipLink=std::nullopt)
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
CbMoveEndEffectorTrajectory(const std::vector< geometry_msgs::msg::PoseStamped > &endEffectorTrajectory, std::optional< std::string > tipLink=std::nullopt)
rclcpp::Client< moveit_msgs::srv::GetPositionIK >::SharedPtr iksrv_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
Component for joint space trajectory generation from Cartesian waypoints.
JointTrajectoryResult planFromWaypoints(const std::vector< geometry_msgs::msg::PoseStamped > &waypoints, const JointTrajectoryOptions &options={})
Compute joint space trajectory from Cartesian waypoints.
Component for shared TF2 transform management across all behaviors.
std::optional< geometry_msgs::msg::TransformStamped > lookupTransform(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time=rclcpp::Time(0))
Thread-safe transform lookup.
Component for centralized trajectory execution.
ExecutionResult execute(const moveit_msgs::msg::RobotTrajectory &trajectory, const ExecutionOptions &options={})
Execute a trajectory synchronously.
void pushTrajectory(std::string name, const moveit_msgs::msg::RobotTrajectory &trajectory, moveit_msgs::msg::MoveItErrorCodes result)
Component for visualizing trajectories as RViz markers.
void setTrajectory(const std::vector< geometry_msgs::msg::PoseStamped > &poses, const std::string &ns="trajectory")
Set trajectory to visualize.
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
std::string demangleSymbol()
Configuration options for trajectory execution.
std::optional< std::string > trajectoryName
Configuration options for joint space trajectory planning.