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(
116 nh_->get_logger(), "[UndoPathGlobalPlanner] received backward path msg poses ["
117 << lastForwardPathMsg_.poses.size() << "]");
118}
119
126{
127 visualization_msgs::msg::Marker marker;
128 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
129 marker.header.stamp = nh_->now();
130 marker.ns = "my_namespace2";
131 marker.id = 0;
132 marker.action = visualization_msgs::msg::Marker::DELETEALL;
133
134 visualization_msgs::msg::MarkerArray ma;
135 ma.markers.push_back(marker);
136 markersPub_->publish(ma);
137}
138
145 const geometry_msgs::msg::Pose & pose, double r, double g, double b)
146{
147 double phi = tf2::getYaw(pose.orientation);
148
149 visualization_msgs::msg::Marker marker;
150 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
151 marker.header.stamp = nh_->now();
152 marker.ns = "my_namespace2";
153 marker.id = 0;
154 marker.type = visualization_msgs::msg::Marker::ARROW;
155 marker.action = visualization_msgs::msg::Marker::ADD;
156 marker.scale.x = 0.1;
157 marker.scale.y = 0.3;
158 marker.scale.z = 0.1;
159 marker.color.a = 1.0;
160
161 marker.color.r = r;
162 marker.color.g = g;
163 marker.color.b = b;
164
165 marker.lifetime = rclcpp::Duration(0s);
166
167 geometry_msgs::msg::Point start, end;
168 start.x = pose.position.x;
169 start.y = pose.position.y;
170
171 end.x = pose.position.x + 0.5 * cos(phi);
172 end.y = pose.position.y + 0.5 * sin(phi);
173
174 marker.points.push_back(start);
175 marker.points.push_back(end);
176
177 visualization_msgs::msg::MarkerArray ma;
178 ma.markers.push_back(marker);
179
180 markersPub_->publish(ma);
181}
188 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & /*goal*/,
189 std::vector<geometry_msgs::msg::PoseStamped> & plan)
190{
191 //------------- TRANSFORM TO GLOBAL FRAME PATH ---------------------------
192 // the forward plan might be recoreded in a different frame of the global (costmap) frame. Transform it.
193 // transform global plan to the navigation reference frame
194
195 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Transforming forward path");
196 nav_msgs::msg::Path transformedPlan;
197 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
198 for (auto p : lastForwardPathMsg_.poses)
199 {
200 geometry_msgs::msg::PoseStamped transformedPose;
201 p.header.stamp = nh_->now(); // otherwise we can get some time tolerance error
202 transformedPose.header.stamp = nh_->now();
203 transformedPose.header.frame_id = costmap_ros_->getGlobalFrameID();
204 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), p, transformedPose, ttol);
205 transformedPlan.poses.push_back(transformedPose);
206 }
207
208 lastForwardPathMsg_ = transformedPlan;
209 //---------------------------------------------------------------------------
210
211 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] finding goal closest point");
212 int i = lastForwardPathMsg_.poses.size() - 1;
213 double linear_mindist = std::numeric_limits<double>::max();
214 int mindistindex = -1;
215 double startPoseAngle = tf2::getYaw(start.pose.orientation);
216 geometry_msgs::msg::Pose startPositionProjected;
217
218 // The goal of this code is finding the most convenient initial path pose.
219 // first, find closest linear point to the current robot position
220 // we start from the final goal, that is, the beginning of the trajectory
221 // (since this was the forward motion from the odom tracker)
222 for (auto & p : transformedPlan.poses /*| boost::adaptors::reversed*/)
223 {
224 geometry_msgs::msg::PoseStamped pose = p;
225 pose.header.frame_id = costmap_ros_->getGlobalFrameID();
226
227 double dx = pose.pose.position.x - start.pose.position.x;
228 double dy = pose.pose.position.y - start.pose.position.y;
229
230 double dist = sqrt(dx * dx + dy * dy);
231 double angleOrientation = tf2::getYaw(pose.pose.orientation);
232 double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
233 if (dist <= linear_mindist)
234 {
235 mindistindex = i;
236 linear_mindist = dist;
237 startPositionProjected = pose.pose;
238
239 RCLCPP_INFO_STREAM(
240 nh_->get_logger(), "[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= "
241 << i << ". error, linear: " << linear_mindist
242 << ", angular: " << angleError);
243 }
244 else
245 {
246 RCLCPP_INFO_STREAM(
247 nh_->get_logger(), "[UndoPathGlobalPlanner] initial start point search, skipped= "
248 << i << ". best linear error: " << linear_mindist
249 << ". current error, linear: " << dist << " angular: " << angleError);
250 }
251
252 i--;
253 }
254
255 double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;
256 // Concept of second pass: now we only consider a pure spinning motion in this point. We want to consume some very
257 // close angular targets, (accepting a larger linear minerror of 1.5 besterror. That is, more or less in the same
258 // point).
259
260 RCLCPP_INFO(nh_->get_logger(), "[UndoPathGlobalPlanner] second angular pass");
261 double angularMinDist = std::numeric_limits<double>::max();
262
263 if (mindistindex >= (int)transformedPlan.poses.size())
264 mindistindex =
265 transformedPlan.poses.size() -
266 1; // workaround, something is making a out of bound exception in poses array access
267 {
268 if (transformedPlan.poses.size() == 0)
269 {
270 RCLCPP_WARN_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Warning possible bug");
271 }
272
273 // ------- FULL FORWARD PASS TO FIND THE STARTING POIINT OF THE FORWARD MOTION ------
274 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] second pass loop");
275 for (int i = mindistindex; i >= 0; i--)
276 {
277 // warning this index, i refers to some inverse interpretation from the previous loop,
278 // (last indexes in this path corresponds to the poses closer to our current position)
279 RCLCPP_INFO_STREAM(
280 nh_->get_logger(), "[UndoPathGlobalPlanner] " << i << "/" << transformedPlan.poses.size());
281 auto index = (int)transformedPlan.poses.size() - i - 1;
282 if (index < 0 || (size_t)index >= transformedPlan.poses.size())
283 {
284 RCLCPP_WARN_STREAM(
285 nh_->get_logger(),
286 "[UndoPathGlobalPlanner] this should not happen. Check implementation.");
287 break;
288 }
289 geometry_msgs::msg::PoseStamped pose =
290 transformedPlan.poses[transformedPlan.poses.size() - i - 1];
291
292 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] global frame");
293 pose.header.frame_id = costmap_ros_->getGlobalFrameID();
294
295 double dx = pose.pose.position.x - start.pose.position.x;
296 double dy = pose.pose.position.y - start.pose.position.y;
297
298 double dist = sqrt(dx * dx + dy * dy);
299 if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)
300 {
301 double angleOrientation = tf2::getYaw(pose.pose.orientation);
302 double angleError =
303 fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
304 if (angleError < angularMinDist)
305 {
306 angularMinDist = angleError;
307 mindistindex = i;
308 RCLCPP_INFO_STREAM(
309 nh_->get_logger(),
310 "[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= "
311 << i << ". error, linear: " << dist << "(" << linear_mindist << ")"
312 << ", angular: " << angleError << "(" << angularMinDist << ")");
313 }
314 else
315 {
316 RCLCPP_INFO_STREAM(
317 nh_->get_logger(),
318 "[UndoPathGlobalPlanner] initial start point search (angular update), skipped= "
319 << i << ". error, linear: " << dist << "(" << linear_mindist << ")"
320 << ", angular: " << angleError << "(" << angularMinDist << ")");
321 }
322 }
323 else
324 {
325 RCLCPP_INFO_STREAM(
326 nh_->get_logger(),
327 "[UndoPathGlobalPlanner] initial start point search (angular update) not in linear "
328 "range, skipped= "
329 << i << " linear error: " << dist << "(" << linear_mindist << ")");
330 }
331 }
332 }
333
334 // REVERSE FORWARD PASS
335 if (mindistindex != -1)
336 {
337 // plan.push_back(start);
338
339 RCLCPP_WARN_STREAM(
340 nh_->get_logger(),
341 "[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (, "
342 << transformedPlan.poses.size() << ") poses");
343
344 RCLCPP_WARN_STREAM(
345 nh_->get_logger(), "[UndoPathGlobalPlanner] closer point to goal i="
346 << mindistindex << " (linear min dist " << linear_mindist << ")");
347
348 // copy the path at the inverse direction, but only up to the closest point to the goal in the path (for partial undoing)
349 for (int i = transformedPlan.poses.size() - 1; i >= mindistindex; i--)
350 {
351 auto & pose = transformedPlan.poses[i];
352
353 rclcpp::Time t(pose.header.stamp);
354
355 RCLCPP_INFO_STREAM(
356 nh_->get_logger(),
357 "[UndoPathGlobalPlanner] adding to plan i = " << i << " stamp:" << t.seconds());
358 plan.push_back(pose);
359 }
360 RCLCPP_WARN_STREAM(
361 nh_->get_logger(), "[UndoPathGlobalPlanner] refined plan has " << plan.size() << " points");
362 }
363 else
364 {
365 RCLCPP_ERROR_STREAM(
366 nh_->get_logger(), "[UndoPathGlobalPlanner ] undo global plan size: " << plan.size());
367 }
368}
369
376 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal)
377{
378 // -------------- BASIC CHECKS ---------------------
379
380 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Undo global plan start ");
381 nav_msgs::msg::Path planMsg;
382 std::vector<geometry_msgs::msg::PoseStamped> & plan = planMsg.poses;
383
384 RCLCPP_INFO_STREAM(
385 nh_->get_logger(),
386 "[UndoPathGlobalPlanner] last forward path msg size: " << lastForwardPathMsg_.poses.size());
387
388 RCLCPP_INFO_STREAM(
389 nh_->get_logger(), "[UndoPathGlobalPlanner] last forward path frame id: "
390 << lastForwardPathMsg_.poses.front().header.frame_id);
391 RCLCPP_INFO_STREAM(
392 nh_->get_logger(), "[UndoPathGlobalPlanner] start pose frame id: " << start.header.frame_id);
393 RCLCPP_INFO_STREAM(
394 nh_->get_logger(), "[UndoPathGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
395
396 if (lastForwardPathMsg_.poses.size() == 0)
397 {
398 return planMsg;
399 }
400
401 // ---------- INPUTS ACCOMMODATION -------------------
402 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Inputs accommodation");
403 geometry_msgs::msg::PoseStamped transformedStart, transformedGoal;
404 {
405 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
406
407 geometry_msgs::msg::PoseStamped pstart = start;
408 pstart.header.stamp = nh_->now();
409 nav_2d_utils::transformPose(
410 tf_, costmap_ros_->getGlobalFrameID(), pstart, transformedStart, ttol);
411 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
412
413 // geometry_msgs::msg::PoseStamped pgoal = goal;
414 // pgoal.header.stamp = nh_->now();
415 // nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), pgoal, transformedGoal, ttol);
416 // transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
417
418 //--------------- FORCE GOAL POSE----------------------------
419 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Forced goal");
420 auto forcedGoal =
421 lastForwardPathMsg_.poses[lastForwardPathMsg_.poses.size() - 1]; // FORCE LAST POSE
422 forcedGoal.header.stamp = nh_->now();
423 nav_2d_utils::transformPose(
424 tf_, costmap_ros_->getGlobalFrameID(), forcedGoal, transformedGoal, ttol);
425 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
426 }
427
428 //------------- CREATING GLOBAL PLAN -----------------------------------------------
429 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] Creating undo plan");
430 this->createDefaultUndoPathPlan(transformedStart, transformedGoal, plan);
431 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
432
433 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] publishing goal markers");
434 publishGoalMarker(plan.back().pose, 1.0, 0, 1.0 /*purple color*/);
435
436 //-------- CHECKING VALID PLAN ------------------------------------
437 bool acceptedGlobalPlan = true;
438 RCLCPP_INFO_STREAM(nh_->get_logger(), "[UndoPathGlobalPlanner] valid plan checking");
439
440 auto costmap2d = this->costmap_ros_->getCostmap();
441 for (auto & p : plan)
442 {
443 unsigned int mx, my;
444 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
445 auto cost = costmap2d->getCost(mx, my);
446
447 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
448 {
449 acceptedGlobalPlan = false;
450 break;
451 }
452 }
453
454 //-------- PUBLISHING RESULTS ---------------------------------------
455 RCLCPP_INFO_STREAM(
456 nh_->get_logger(), "[UndoPathGlobalPlanner] plan publishing. size: " << plan.size());
457 planPub_->publish(planMsg);
458 if (!acceptedGlobalPlan)
459 {
460 RCLCPP_INFO(
461 nh_->get_logger(),
462 "[UndoPathGlobalPlanner] not accepted global plan because of possible collision");
463 }
464
465 RCLCPP_INFO_STREAM(
466 nh_->get_logger(), "[UndoPathGlobalPlanner] plan publishing. size: " << planMsg.poses.size());
467
468 return planMsg;
469}
470
471} // namespace undo_path_global_planner
472} // namespace cl_nav2z
473PLUGINLIB_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