SMACC2
Loading...
Searching...
No Matches
cb_move_end_effector_trajectory.cpp
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#include <tf2/transform_datatypes.h>
22#include <tf2_ros/transform_listener.h>
23
27#include <moveit_msgs/srv/get_position_ik.hpp>
28
29#include <visualization_msgs/msg/marker_array.hpp>
30
31using namespace std::chrono_literals;
32
34{
36: tipLink_(tipLink), markersInitialized_(false)
37{
38}
39
41 const std::vector<geometry_msgs::msg::PoseStamped> & endEffectorTrajectory,
42 std::optional<std::string> tipLink)
43: tipLink_(tipLink), endEffectorTrajectory_(endEffectorTrajectory), markersInitialized_(false)
44
45{
46}
47
49{
50 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] initializing ros");
51
52 auto nh = this->getNode();
53 markersPub_ = nh->create_publisher<visualization_msgs::msg::MarkerArray>("trajectory_markers", 1);
54 iksrv_ = nh->create_client<moveit_msgs::srv::GetPositionIK>("/compute_ik");
55}
56
58 moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
59{
60 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting current state.. waiting");
61
62 // get current robot state
63 auto currentState = movegroupClient_->moveGroupClientInterface->getCurrentState(100);
64
65 // get the IK client
66 auto groupname = movegroupClient_->moveGroupClientInterface->getName();
67
68 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting joint names");
69 auto currentjointnames = currentState->getJointModelGroup(groupname)->getActiveJointModelNames();
70
71 if (!tipLink_ || *tipLink_ == "")
72 {
73 tipLink_ = movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
74 }
75
76 std::vector<double> jointPositions;
77 currentState->copyJointGroupPositions(groupname, jointPositions);
78
79 std::vector<std::vector<double>> trajectory;
80 std::vector<rclcpp::Duration> trajectoryTimeStamps;
81
82 trajectory.push_back(jointPositions);
83 trajectoryTimeStamps.push_back(rclcpp::Duration(0s));
84
85 auto & first = endEffectorTrajectory_.front();
86 rclcpp::Time referenceTime(first.header.stamp);
87
88 std::vector<int> discontinuityIndexes;
89
90 int ikAttempts = 4;
91 for (size_t k = 0; k < this->endEffectorTrajectory_.size(); k++)
92 {
93 auto & pose = this->endEffectorTrajectory_[k];
94 auto req = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
95 //req.ik_request.attempts = 20;
96
97 req->ik_request.ik_link_name = *tipLink_;
98 req->ik_request.robot_state.joint_state.name = currentjointnames;
99 req->ik_request.robot_state.joint_state.position = jointPositions;
100
101 req->ik_request.group_name = groupname;
102 req->ik_request.avoid_collisions = true;
103
104 //pose.header.stamp = getNode()->now();
105 req->ik_request.pose_stamped = pose;
106
107 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] IK request: " << k << " " << *req);
108
109 auto resfut = iksrv_->async_send_request(req);
110
111 auto status = resfut.wait_for(3s);
112 if (status == std::future_status::ready)
113 {
114 //if (rclcpp::spin_until_future_complete(getNode(), resfut) == rclcpp::FutureReturnCode::SUCCESS)
115 //{
116 auto & prevtrajpoint = trajectory.back();
117 //jointPositions.clear();
118
119 auto res = resfut.get();
120 std::stringstream ss;
121 for (size_t j = 0; j < res->solution.joint_state.position.size(); j++)
122 {
123 auto & jointname = res->solution.joint_state.name[j];
124 auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);
125 if (it != currentjointnames.end())
126 {
127 int index = std::distance(currentjointnames.begin(), it);
128 jointPositions[index] = res->solution.joint_state.position[j];
129 ss << jointname << "(" << index << "): " << jointPositions[index] << std::endl;
130 }
131 }
132
133 // continuity check
134 size_t jointindex = 0;
135 int discontinuityJointIndex = -1;
136 double discontinuityDeltaJointIndex = -1;
137 double deltajoint;
138
139 bool check = k > 0 || !allowInitialTrajectoryStateJointDiscontinuity_ ||
141 !(*allowInitialTrajectoryStateJointDiscontinuity_));
142 if (check)
143 {
144 for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)
145 {
146 deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];
147
148 if (fabs(deltajoint) > 0.3 /*2.5 deg*/)
149 {
150 discontinuityDeltaJointIndex = deltajoint;
151 discontinuityJointIndex = jointindex;
152 }
153 }
154 }
155
156 if (ikAttempts > 0 && discontinuityJointIndex != -1)
157 {
158 k--;
159 ikAttempts--;
160 continue;
161 }
162 else
163 {
164 bool discontinuity = false;
165 if (ikAttempts == 0)
166 {
167 discontinuityIndexes.push_back(k);
168 discontinuity = true;
169 }
170
171 ikAttempts = 4;
172
173 if (discontinuity && discontinuityJointIndex != -1)
174 {
175 // show a message and stop the trajectory generation && jointindex!= 7 || fabs(deltajoint) > 0.1 /*2.5 deg*/ && jointindex== 7
176 std::stringstream ss;
177 ss << "Traj[" << k << "/" << endEffectorTrajectory_.size() << "] "
178 << currentjointnames[discontinuityJointIndex]
179 << " IK discontinuity : " << discontinuityDeltaJointIndex << std::endl
180 << "prev joint value: " << prevtrajpoint[discontinuityJointIndex] << std::endl
181 << "current joint value: " << jointPositions[discontinuityJointIndex] << std::endl;
182
183 ss << std::endl;
184 for (size_t ji = 0; ji < jointPositions.size(); ji++)
185 {
186 ss << currentjointnames[ji] << ": " << jointPositions[ji] << std::endl;
187 }
188
189 for (size_t kindex = 0; kindex < trajectory.size(); kindex++)
190 {
191 ss << "[" << kindex << "]: " << trajectory[kindex][discontinuityJointIndex]
192 << std::endl;
193 }
194
195 if (k == 0)
196 {
197 ss << "This is the first posture of the trajectory. Maybe the robot initial posture is "
198 "not coincident to the initial posture of the generated joint trajectory."
199 << std::endl;
200 }
201
202 RCLCPP_ERROR_STREAM(getLogger(), ss.str());
203
204 trajectory.push_back(jointPositions);
205 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
206 trajectoryTimeStamps.push_back(durationFromStart);
207
208 continue;
209 }
210 else
211 {
212 trajectory.push_back(jointPositions);
213 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
214 trajectoryTimeStamps.push_back(durationFromStart);
215
216 RCLCPP_DEBUG_STREAM(getLogger(), "IK solution: " << res->solution.joint_state);
217 RCLCPP_DEBUG_STREAM(getLogger(), "trajpoint: " << std::endl << ss.str());
218 }
219 }
220 }
221 else
222 {
223 RCLCPP_ERROR_STREAM(getLogger(), "[" << getName() << "] wrong IK call");
224 }
225 }
226
227 // interpolate speeds?
228
229 // interpolate accelerations?
230
231 // get current robot state
232 // fill plan message
233 // computedMotionPlan.start_state_.joint_state.name = currentjointnames;
234 // computedMotionPlan.start_state_.joint_state.position = trajectory.front();
235 // computedMotionPlan.trajectory_.joint_trajectory.joint_names = currentjointnames;
236
237 computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;
238 int i = 0;
239 for (auto & p : trajectory)
240 {
241 if (
242 i ==
243 0) // not copy the current state in the trajectory (used to solve discontinuity in other behaviors)
244 {
245 i++;
246 continue;
247 }
248
249 trajectory_msgs::msg::JointTrajectoryPoint jp;
250 jp.positions = p;
251 jp.time_from_start = trajectoryTimeStamps[i]; //rclcpp::Duration(t);
252 computedJointTrajectory.joint_trajectory.points.push_back(jp);
253 i++;
254 }
255
256 if (discontinuityIndexes.size())
257 {
258 if (discontinuityIndexes[0] == 0)
260 else
262 }
263
265}
266
268 const moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
269{
270 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Executing joint trajectory");
271 // call execute
272 auto executionResult =
273 this->movegroupClient_->moveGroupClientInterface->execute(computedJointTrajectory);
274
275 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
276 {
277 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] motion execution succeeded");
279 this->postSuccessEvent();
280 }
281 else
282 {
284 this->postFailureEvent();
285 }
286}
287
289{
291
292 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Generating end effector trajectory");
293
294 this->generateTrajectory();
295
296 if (this->endEffectorTrajectory_.size() == 0)
297 {
298 RCLCPP_WARN_STREAM(
299 getLogger(), "[" << smacc2::demangleSymbol(typeid(*this).name())
300 << "] No points in the trajectory. Skipping behavior.");
301 return;
302 }
303
304 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Creating markers.");
305
306 this->createMarkers();
307 markersInitialized_ = true;
308 moveit_msgs::msg::RobotTrajectory computedTrajectory;
309
310 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Computing joint space trajectory.");
311
312 auto errorcode = computeJointSpaceTrajectory(computedTrajectory);
313
314 bool trajectoryGenerationSuccess = errorcode == ComputeJointTrajectoryErrorCode::SUCCESS;
315
316 CpTrajectoryHistory * trajectoryHistory;
317 this->requiresComponent(trajectoryHistory);
318
319 if (!trajectoryGenerationSuccess)
320 {
321 RCLCPP_INFO_STREAM(
322 getLogger(), "[" << this->getName() << "] Incorrect trajectory. Posting failure event.");
323 if (trajectoryHistory != nullptr)
324 {
325 moveit_msgs::msg::MoveItErrorCodes error;
326 error.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
327 trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);
328 }
329
331 this->postFailureEvent();
332
334 {
335 this->postJointDiscontinuityEvent(computedTrajectory);
336 }
338 {
339 this->postIncorrectInitialStateEvent(computedTrajectory);
340 }
341 return;
342 }
343 else
344 {
345 if (trajectoryHistory != nullptr)
346 {
347 moveit_msgs::msg::MoveItErrorCodes error;
348 error.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
349 trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);
350 }
351
352 this->executeJointSpaceTrajectory(computedTrajectory);
353 }
354
355 // handle finishing events
356} // namespace cl_move_group_interface
357
359{
361 {
362 std::lock_guard<std::mutex> guard(m_mutex_);
364 }
365}
366
368{
369 markersInitialized_ = false;
370
372 {
373 std::lock_guard<std::mutex> guard(m_mutex_);
374 for (auto & marker : this->beahiorMarkers_.markers)
375 {
376 marker.header.stamp = getNode()->now();
377 marker.action = visualization_msgs::msg::Marker::DELETE;
378 }
379
381 }
382}
383
385{
386 tf2::Transform localdirection;
387 localdirection.setIdentity();
388 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
389 auto frameid = this->endEffectorTrajectory_.front().header.frame_id;
390
391 for (auto & pose : this->endEffectorTrajectory_)
392 {
393 visualization_msgs::msg::Marker marker;
394 marker.header.frame_id = frameid;
395 marker.header.stamp = getNode()->now();
396 marker.ns = "trajectory";
397 marker.id = this->beahiorMarkers_.markers.size();
398 marker.type = visualization_msgs::msg::Marker::ARROW;
399 marker.action = visualization_msgs::msg::Marker::ADD;
400 marker.scale.x = 0.005;
401 marker.scale.y = 0.01;
402 marker.scale.z = 0.01;
403 marker.color.a = 0.8;
404 marker.color.r = 1.0;
405 marker.color.g = 0;
406 marker.color.b = 0;
407
408 geometry_msgs::msg::Point start, end;
409 start.x = 0;
410 start.y = 0;
411 start.z = 0;
412
413 tf2::Transform basetransform;
414 tf2::fromMsg(pose.pose, basetransform);
415 // tf2::Transform endarrow = localdirection * basetransform;
416
417 end.x = localdirection.getOrigin().x();
418 end.y = localdirection.getOrigin().y();
419 end.z = localdirection.getOrigin().z();
420
421 marker.pose.position = pose.pose.position;
422 marker.pose.orientation = pose.pose.orientation;
423 marker.points.push_back(start);
424 marker.points.push_back(end);
425
426 beahiorMarkers_.markers.push_back(marker);
427 }
428}
429
431{
432 // bypass current trajectory, overridden in derived classes
433 // this->endEffectorTrajectory_ = ...
434}
435
437 std::string globalFrame, tf2::Stamped<tf2::Transform> & currentEndEffectorTransform)
438{
439 tf2_ros::Buffer tfBuffer(getNode()->get_clock());
440 tf2_ros::TransformListener tfListener(tfBuffer);
441
442 try
443 {
444 if (!tipLink_ || *tipLink_ == "")
445 {
446 tipLink_ = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
447 }
448
449 tf2::fromMsg(
450 tfBuffer.lookupTransform(globalFrame, *tipLink_, rclcpp::Time(0), rclcpp::Duration(10s)),
451 currentEndEffectorTransform);
452
453 //tfListener.lookupTransform(globalFrame, *tipLink_, rclcpp::Time(0), currentEndEffectorTransform);
454
455 // we define here the global frame as the pivot frame id
456 // tfListener.waitForTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, rclcpp::Time(0), rclcpp::Duration(10));
457 // tfListener.lookupTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, rclcpp::Time(0), globalBaseLink);
458 }
459 catch (const std::exception & e)
460 {
461 std::cerr << e.what() << std::endl;
462 }
463}
464} // namespace cl_move_group_interface
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postIncorrectInitialStateEvent
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
std::function< void(moveit_msgs::msg::RobotTrajectory &)> postJointDiscontinuityEvent
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
rclcpp::Client< moveit_msgs::srv::GetPositionIK >::SharedPtr iksrv_
CbMoveEndEffectorTrajectory(std::optional< std::string > tipLink=std::nullopt)
void executeJointSpaceTrajectory(const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
void pushTrajectory(std::string name, const moveit_msgs::msg::RobotTrajectory &trajectory, moveit_msgs::msg::MoveItErrorCodes result)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
std::string demangleSymbol()