SMACC2
Loading...
Searching...
No Matches
undo_path_global_planner.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 <angles/angles.h>
22#include <tf2/transform_datatypes.h>
23
24#include <boost/assign.hpp>
25#include <boost/range/adaptor/reversed.hpp>
26#include <boost/range/algorithm/copy.hpp>
27#include <geometry_msgs/msg/quaternion.hpp>
28
30#include <nav_2d_utils/tf_help.hpp>
31#include <pluginlib/class_list_macros.hpp>
32#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
34
35// register this planner as a BaseGlobalPlanner plugin
36namespace cl_nav2z
37{
38namespace undo_path_global_planner
39{
40using namespace std::chrono_literals;
41
52
54{
55 // clear "rviz"- publish empty path
56 nav_msgs::msg::Path planMsg;
57 planMsg.header.stamp = this->nh_->now();
58 planPub_->publish(planMsg);
59}
60
62
64{
65 RCLCPP_INFO_STREAM(nh_->get_logger(), "activating planner UndoPathGlobalPlanner");
66 planPub_->on_activate();
67 markersPub_->on_activate();
68}
69
71{
72 RCLCPP_INFO_STREAM(nh_->get_logger(), "deactivating planner UndoPathGlobalPlanner");
73 this->clearGoalMarker();
74 planPub_->on_deactivate();
75 markersPub_->on_deactivate();
76}
77
84 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
85 std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
86{
87 nh_ = parent.lock();
88 costmap_ros_ = costmap_ros;
89 tf_ = tf;
90 name_ = name;
91 // RCLCPP_WARN_NAMED(nh_->get_logger(), "Backwards", "initializating global planner, costmap address: %ld",
92 // (long)costmap_ros);
93
94 rclcpp::SensorDataQoS qos;
95 qos.keep_last(2);
96 forwardPathSub_ = nh_->create_subscription<nav_msgs::msg::Path>(
97 "odom_tracker_path", qos,
98 std::bind(&UndoPathGlobalPlanner::onForwardTrailMsg, this, std::placeholders::_1));
99
100 planPub_ =
101 nh_->create_publisher<nav_msgs::msg::Path>("undo_path_planner/global_plan", rclcpp::QoS(1));
102 markersPub_ = nh_->create_publisher<visualization_msgs::msg::MarkerArray>(
103 "undo_path_planner/markers", rclcpp::QoS(1));
104
105 declareOrSet(nh_, name_ + ".transform_tolerance", transform_tolerance_);
106}
112void UndoPathGlobalPlanner::onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr forwardPath)
113{
114 lastForwardPathMsg_ = *forwardPath;
115 RCLCPP_INFO_STREAM_THROTTLE(
116 nh_->get_logger(), *nh_, 1000,
117 "[UndoPathGlobalPlanner] received backward path msg poses [" << lastForwardPathMsg_.poses.size()
118 << "]");
119}
120
127{
128 visualization_msgs::msg::Marker marker;
129 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
130 marker.header.stamp = nh_->now();
131 marker.ns = "my_namespace2";
132 marker.id = 0;
133 marker.action = visualization_msgs::msg::Marker::DELETEALL;
134
135 visualization_msgs::msg::MarkerArray ma;
136 ma.markers.push_back(marker);
137 markersPub_->publish(ma);
138}
139
146 const geometry_msgs::msg::Pose & pose, double r, double g, double b)
147{
148 double phi = tf2::getYaw(pose.orientation);
149
150 visualization_msgs::msg::Marker marker;
151 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
152 marker.header.stamp = nh_->now();
153 marker.ns = "my_namespace2";
154 marker.id = 0;
155 marker.type = visualization_msgs::msg::Marker::ARROW;
156 marker.action = visualization_msgs::msg::Marker::ADD;
157 marker.scale.x = 0.1;
158 marker.scale.y = 0.3;
159 marker.scale.z = 0.1;
160 marker.color.a = 1.0;
161
162 marker.color.r = r;
163 marker.color.g = g;
164 marker.color.b = b;
165
166 marker.lifetime = rclcpp::Duration(0s);
167
168 geometry_msgs::msg::Point start, end;
169 start.x = pose.position.x;
170 start.y = pose.position.y;
171
172 end.x = pose.position.x + 0.5 * cos(phi);
173 end.y = pose.position.y + 0.5 * sin(phi);
174
175 marker.points.push_back(start);
176 marker.points.push_back(end);
177
178 visualization_msgs::msg::MarkerArray ma;
179 ma.markers.push_back(marker);
180
181 markersPub_->publish(ma);
182}
189 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & /*goal*/,
190 std::vector<geometry_msgs::msg::PoseStamped> & plan)
191{
192 //------------- TRANSFORM TO GLOBAL FRAME PATH ---------------------------
193 // the forward plan might be recoreded in a different frame of the global (costmap) frame. Transform it.
194 // transform global plan to the navigation reference frame
195
196 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Transforming forward path");
197 nav_msgs::msg::Path transformedPlan;
198 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
199 for (auto p : lastForwardPathMsg_.poses)
200 {
201 geometry_msgs::msg::PoseStamped transformedPose;
202 p.header.stamp = nh_->now(); // otherwise we can get some time tolerance error
203 transformedPose.header.stamp = nh_->now();
204 transformedPose.header.frame_id = costmap_ros_->getGlobalFrameID();
205 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), p, transformedPose, ttol);
206 transformedPlan.poses.push_back(transformedPose);
207 }
208
209 lastForwardPathMsg_ = transformedPlan;
210 //---------------------------------------------------------------------------
211
212 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] finding goal closest point");
213 int i = lastForwardPathMsg_.poses.size() - 1;
214 double linear_mindist = std::numeric_limits<double>::max();
215 int mindistindex = -1;
216 double startPoseAngle = tf2::getYaw(start.pose.orientation);
217 geometry_msgs::msg::Pose startPositionProjected;
218
219 // The goal of this code is finding the most convenient initial path pose.
220 // first, find closest linear point to the current robot position
221 // we start from the final goal, that is, the beginning of the trajectory
222 // (since this was the forward motion from the odom tracker)
223 for (auto & p : transformedPlan.poses /*| boost::adaptors::reversed*/)
224 {
225 geometry_msgs::msg::PoseStamped pose = p;
226 pose.header.frame_id = costmap_ros_->getGlobalFrameID();
227
228 double dx = pose.pose.position.x - start.pose.position.x;
229 double dy = pose.pose.position.y - start.pose.position.y;
230
231 double dist = sqrt(dx * dx + dy * dy);
232 double angleOrientation = tf2::getYaw(pose.pose.orientation);
233 double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
234 if (dist <= linear_mindist)
235 {
236 mindistindex = i;
237 linear_mindist = dist;
238 startPositionProjected = pose.pose;
239
240 RCLCPP_INFO_STREAM(
241 nh_->get_logger(), "[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= "
242 << i << ". error, linear: " << linear_mindist
243 << ", angular: " << angleError);
244 }
245 else
246 {
247 RCLCPP_INFO_STREAM(
248 nh_->get_logger(), "[UndoPathGlobalPlanner] initial start point search, skipped= "
249 << i << ". best linear error: " << linear_mindist
250 << ". current error, linear: " << dist << " angular: " << angleError);
251 }
252
253 i--;
254 }
255
256 double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;
257 // Concept of second pass: now we only consider a pure spinning motion in this point. We want to consume some very
258 // close angular targets, (accepting a larger linear minerror of 1.5 besterror. That is, more or less in the same
259 // point).
260
261 RCLCPP_INFO(nh_->get_logger(), "[UndoPathGlobalPlanner] second angular pass");
262 double angularMinDist = std::numeric_limits<double>::max();
263
264 if (mindistindex >= (int)transformedPlan.poses.size())
265 mindistindex =
266 transformedPlan.poses.size() -
267 1; // workaround, something is making a out of bound exception in poses array access
268 {
269 if (transformedPlan.poses.size() == 0)
270 {
271 RCLCPP_WARN_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Warning possible bug");
272 }
273
274 // ------- FULL FORWARD PASS TO FIND THE STARTING POIINT OF THE FORWARD MOTION ------
275 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] second pass loop");
276 for (int i = mindistindex; i >= 0; i--)
277 {
278 // warning this index, i refers to some inverse interpretation from the previous loop,
279 // (last indexes in this path corresponds to the poses closer to our current position)
280 RCLCPP_INFO_STREAM(
281 nh_->get_logger(), "[UndoPathGlobalPlanner] " << i << "/" << transformedPlan.poses.size());
282 auto index = (int)transformedPlan.poses.size() - i - 1;
283 if (index < 0 || (size_t)index >= transformedPlan.poses.size())
284 {
285 RCLCPP_WARN_STREAM(
286 nh_->get_logger(),
287 "[UndoPathGlobalPlanner] this should not happen. Check implementation.");
288 break;
289 }
290 geometry_msgs::msg::PoseStamped pose =
291 transformedPlan.poses[transformedPlan.poses.size() - i - 1];
292
293 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] global frame");
294 pose.header.frame_id = costmap_ros_->getGlobalFrameID();
295
296 double dx = pose.pose.position.x - start.pose.position.x;
297 double dy = pose.pose.position.y - start.pose.position.y;
298
299 double dist = sqrt(dx * dx + dy * dy);
300 if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)
301 {
302 double angleOrientation = tf2::getYaw(pose.pose.orientation);
303 double angleError =
304 fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
305 if (angleError < angularMinDist)
306 {
307 angularMinDist = angleError;
308 mindistindex = i;
309 RCLCPP_INFO_STREAM(
310 nh_->get_logger(),
311 "[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= "
312 << i << ". error, linear: " << dist << "(" << linear_mindist << ")"
313 << ", angular: " << angleError << "(" << angularMinDist << ")");
314 }
315 else
316 {
317 RCLCPP_INFO_STREAM(
318 nh_->get_logger(),
319 "[UndoPathGlobalPlanner] initial start point search (angular update), skipped= "
320 << i << ". error, linear: " << dist << "(" << linear_mindist << ")"
321 << ", angular: " << angleError << "(" << angularMinDist << ")");
322 }
323 }
324 else
325 {
326 RCLCPP_INFO_STREAM(
327 nh_->get_logger(),
328 "[UndoPathGlobalPlanner] initial start point search (angular update) not in linear "
329 "range, skipped= "
330 << i << " linear error: " << dist << "(" << linear_mindist << ")");
331 }
332 }
333 }
334
335 // REVERSE FORWARD PASS
336 if (mindistindex != -1)
337 {
338 // plan.push_back(start);
339
340 RCLCPP_WARN_STREAM(
341 nh_->get_logger(),
342 "[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (, "
343 << transformedPlan.poses.size() << ") poses");
344
345 RCLCPP_WARN_STREAM(
346 nh_->get_logger(), "[UndoPathGlobalPlanner] closer point to goal i="
347 << mindistindex << " (linear min dist " << linear_mindist << ")");
348
349 // copy the path at the inverse direction, but only up to the closest point to the goal in the path (for partial undoing)
350 for (int i = transformedPlan.poses.size() - 1; i >= mindistindex; i--)
351 {
352 auto & pose = transformedPlan.poses[i];
353
354 rclcpp::Time t(pose.header.stamp);
355
356 RCLCPP_INFO_STREAM(
357 nh_->get_logger(),
358 "[UndoPathGlobalPlanner] adding to plan i = " << i << " stamp:" << t.seconds());
359 plan.push_back(pose);
360 }
361 RCLCPP_WARN_STREAM(
362 nh_->get_logger(), "[UndoPathGlobalPlanner] refined plan has " << plan.size() << " points");
363 }
364 else
365 {
366 RCLCPP_ERROR_STREAM(
367 nh_->get_logger(), "[UndoPathGlobalPlanner ] undo global plan size: " << plan.size());
368 }
369}
370
377 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal)
378{
379 // -------------- BASIC CHECKS ---------------------
380
381 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Undo global plan start ");
382 nav_msgs::msg::Path planMsg;
383 std::vector<geometry_msgs::msg::PoseStamped> & plan = planMsg.poses;
384
385 RCLCPP_INFO_STREAM(
386 nh_->get_logger(),
387 "[UndoPathGlobalPlanner] last forward path msg size: " << lastForwardPathMsg_.poses.size());
388
389 RCLCPP_INFO_STREAM(
390 nh_->get_logger(), "[UndoPathGlobalPlanner] last forward path frame id: "
391 << lastForwardPathMsg_.poses.front().header.frame_id);
392 RCLCPP_INFO_STREAM(
393 nh_->get_logger(), "[UndoPathGlobalPlanner] start pose frame id: " << start.header.frame_id);
394 RCLCPP_INFO_STREAM(
395 nh_->get_logger(), "[UndoPathGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
396
397 if (lastForwardPathMsg_.poses.size() == 0)
398 {
399 return planMsg;
400 }
401
402 // ---------- INPUTS ACCOMMODATION -------------------
403 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Inputs accommodation");
404 geometry_msgs::msg::PoseStamped transformedStart, transformedGoal;
405 {
406 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
407
408 geometry_msgs::msg::PoseStamped pstart = start;
409 pstart.header.stamp = nh_->now();
410 nav_2d_utils::transformPose(
411 tf_, costmap_ros_->getGlobalFrameID(), pstart, transformedStart, ttol);
412 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
413
414 // geometry_msgs::msg::PoseStamped pgoal = goal;
415 // pgoal.header.stamp = nh_->now();
416 // nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), pgoal, transformedGoal, ttol);
417 // transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
418
419 //--------------- FORCE GOAL POSE----------------------------
420 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Forced goal");
421 auto forcedGoal =
422 lastForwardPathMsg_.poses[lastForwardPathMsg_.poses.size() - 1]; // FORCE LAST POSE
423 forcedGoal.header.stamp = nh_->now();
424 nav_2d_utils::transformPose(
425 tf_, costmap_ros_->getGlobalFrameID(), forcedGoal, transformedGoal, ttol);
426 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
427 }
428
429 //------------- CREATING GLOBAL PLAN -----------------------------------------------
430 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Creating undo plan");
431 this->createDefaultUndoPathPlan(transformedStart, transformedGoal, plan);
432 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
433
434 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] publishing goal markers");
435 publishGoalMarker(plan.back().pose, 1.0, 0, 1.0 /*purple color*/);
436
437 //-------- CHECKING VALID PLAN ------------------------------------
438 bool acceptedGlobalPlan = true;
439 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] valid plan checking");
440
441 auto costmap2d = this->costmap_ros_->getCostmap();
442 for (auto & p : plan)
443 {
444 unsigned int mx, my;
445 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
446 auto cost = costmap2d->getCost(mx, my);
447
448 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
449 {
450 acceptedGlobalPlan = false;
451 break;
452 }
453 }
454
455 // if(planMsg.poses.size() == 1)
456 // planMsg.poses.clear();
457
458 //-------- PUBLISHING RESULTS ---------------------------------------
459 RCLCPP_INFO_STREAM(
460 nh_->get_logger(), "[UndoPathGlobalPlanner] plan publishing. size: " << plan.size());
461 planPub_->publish(planMsg);
462 if (!acceptedGlobalPlan)
463 {
464 RCLCPP_INFO(
465 nh_->get_logger(),
466 "[UndoPathGlobalPlanner] not accepted global plan because of possible collision");
467 }
468
469 RCLCPP_INFO_STREAM(
470 nh_->get_logger(), "[UndoPathGlobalPlanner] plan publishing. size: " << planMsg.poses.size());
471
472 return planMsg;
473}
474
475} // namespace undo_path_global_planner
476} // namespace cl_nav2z
477PLUGINLIB_EXPORT_CLASS(
virtual nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)
Method create the plan from a starting and ending goal.
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
virtual void cleanup()
Method to cleanup resources used on shutdown.
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr markersPub_
virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
rclcpp::Subscription< nav_msgs::msg::Path >::SharedPtr forwardPathSub_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr planPub_
virtual void activate()
Method to active planner and any threads involved in execution.
void onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr trailMessage)
void publishGoalMarker(const geometry_msgs::msg::Pose &pose, double r, double g, double b)
virtual void createDefaultUndoPathPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::vector< geometry_msgs::msg::PoseStamped > &plan)
void declareOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)
Definition common.hpp:34