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