21#include <angles/angles.h>
22#include <tf2/transform_datatypes.h>
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>
29#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
31#include <nav_2d_utils/tf_help.hpp>
32#include <pluginlib/class_list_macros.hpp>
38namespace undo_path_global_planner
40using namespace std::chrono_literals;
56 nav_msgs::msg::Path planMsg;
57 planMsg.header.stamp = this->
nh_->now();
65 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"activating planner UndoPathGlobalPlanner");
72 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"deactivating planner UndoPathGlobalPlanner");
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)
94 rclcpp::SensorDataQoS qos;
97 "odom_tracker_path", qos,
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);
115 nh_->get_logger(),
"[UndoPathGlobalPlanner] received backward path msg poses ["
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";
131 marker.action = visualization_msgs::msg::Marker::DELETEALL;
133 visualization_msgs::msg::MarkerArray ma;
134 ma.markers.push_back(marker);
144 const geometry_msgs::msg::Pose & pose,
double r,
double g,
double b)
146 double phi = tf2::getYaw(pose.orientation);
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";
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;
164 marker.lifetime = rclcpp::Duration(0s);
166 geometry_msgs::msg::Point start, end;
167 start.x = pose.position.x;
168 start.y = pose.position.y;
170 end.x = pose.position.x + 0.5 * cos(phi);
171 end.y = pose.position.y + 0.5 * sin(phi);
173 marker.points.push_back(start);
174 marker.points.push_back(end);
176 visualization_msgs::msg::MarkerArray ma;
177 ma.markers.push_back(marker);
187 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & ,
188 std::vector<geometry_msgs::msg::PoseStamped> & plan)
194 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Transforming forward path");
195 nav_msgs::msg::Path transformedPlan;
199 geometry_msgs::msg::PoseStamped transformedPose;
200 p.header.stamp =
nh_->now();
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);
210 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] finding goal closest point");
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;
221 for (
auto & p : transformedPlan.poses )
223 geometry_msgs::msg::PoseStamped pose = p;
224 pose.header.frame_id =
costmap_ros_->getGlobalFrameID();
226 double dx = pose.pose.position.x - start.pose.position.x;
227 double dy = pose.pose.position.y - start.pose.position.y;
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)
235 linear_mindist = dist;
236 startPositionProjected = pose.pose;
239 nh_->get_logger(),
"[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= "
240 << i <<
". error, linear: " << linear_mindist
241 <<
", angular: " << angleError);
246 nh_->get_logger(),
"[UndoPathGlobalPlanner] initial start point search, skipped= "
247 << i <<
". best linear error: " << linear_mindist
248 <<
". current error, linear: " << dist <<
" angular: " << angleError);
254 double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;
259 RCLCPP_DEBUG(
nh_->get_logger(),
"[UndoPathGlobalPlanner] second angular pass");
260 double angularMinDist = std::numeric_limits<double>::max();
262 if (mindistindex >= (
int)transformedPlan.poses.size())
264 transformedPlan.poses.size() -
267 if (transformedPlan.poses.size() == 0)
269 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Warning possible bug");
273 RCLCPP_DEBUG_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] second pass loop");
274 for (
int i = mindistindex; i >= 0; i--)
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())
285 "[UndoPathGlobalPlanner] this should not happen. Check implementation.");
288 geometry_msgs::msg::PoseStamped pose =
289 transformedPlan.poses[transformedPlan.poses.size() - i - 1];
291 RCLCPP_DEBUG_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] global frame");
292 pose.header.frame_id =
costmap_ros_->getGlobalFrameID();
294 double dx = pose.pose.position.x - start.pose.position.x;
295 double dy = pose.pose.position.y - start.pose.position.y;
297 double dist = sqrt(dx * dx + dy * dy);
298 if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)
300 double angleOrientation = tf2::getYaw(pose.pose.orientation);
302 fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
303 if (angleError < angularMinDist)
305 angularMinDist = angleError;
309 "[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= "
310 << i <<
". error, linear: " << dist <<
"(" << linear_mindist <<
")"
311 <<
", angular: " << angleError <<
"(" << angularMinDist <<
")");
317 "[UndoPathGlobalPlanner] initial start point search (angular update), skipped= "
318 << i <<
". error, linear: " << dist <<
"(" << linear_mindist <<
")"
319 <<
", angular: " << angleError <<
"(" << angularMinDist <<
")");
326 "[UndoPathGlobalPlanner] initial start point search (angular update) not in linear "
328 << i <<
" linear error: " << dist <<
"(" << linear_mindist <<
")");
334 if (mindistindex != -1)
340 "[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (, "
341 << transformedPlan.poses.size() <<
") poses");
344 nh_->get_logger(),
"[UndoPathGlobalPlanner] closer point to goal i="
345 << mindistindex <<
" (linear min dist " << linear_mindist <<
")");
348 for (
int i = transformedPlan.poses.size() - 1; i >= mindistindex; i--)
350 auto & pose = transformedPlan.poses[i];
352 rclcpp::Time t(pose.header.stamp);
356 "[UndoPathGlobalPlanner] adding to plan i = " << i <<
" stamp:" << t.seconds());
357 plan.push_back(pose);
360 nh_->get_logger(),
"[UndoPathGlobalPlanner] refined plan has " << plan.size() <<
" points");
365 nh_->get_logger(),
"[UndoPathGlobalPlanner ] undo global plan size: " << plan.size());
375 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal)
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;
385 "[UndoPathGlobalPlanner] last forward path msg size: " <<
lastForwardPathMsg_.poses.size());
387 nh_->get_logger(),
"[UndoPathGlobalPlanner] last forward path frame id: "
390 nh_->get_logger(),
"[UndoPathGlobalPlanner] start pose frame id: " << start.header.frame_id);
392 nh_->get_logger(),
"[UndoPathGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
400 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Inputs accommodation");
401 geometry_msgs::msg::PoseStamped transformedStart, transformedGoal;
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();
417 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Forced goal");
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();
427 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Creating undo plan");
429 planMsg.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
431 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] publishing goal markers");
435 bool acceptedGlobalPlan =
true;
436 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] valid plan checking");
439 for (
auto & p : plan)
442 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
443 auto cost = costmap2d->getCost(mx, my);
445 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
447 acceptedGlobalPlan =
false;
454 nh_->get_logger(),
"[UndoPathGlobalPlanner] plan publishing. size: " << plan.size());
456 if (!acceptedGlobalPlan)
460 "[UndoPathGlobalPlanner] not accepted global plan because of possible collision");
464 nh_->get_logger(),
"[UndoPathGlobalPlanner] plan publishing. size: " << planMsg.poses.size());
471PLUGINLIB_EXPORT_CLASS(
rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
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_
double skip_straight_motion_distance_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
std::shared_ptr< tf2_ros::Buffer > tf_
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr planPub_
virtual void activate()
Method to active planner and any threads involved in execution.
virtual ~UndoPathGlobalPlanner()
Virtual destructor.
void onForwardTrailMsg(const nav_msgs::msg::Path::SharedPtr trailMessage)
void publishGoalMarker(const geometry_msgs::msg::Pose &pose, double r, double g, double b)
double transform_tolerance_
virtual void createDefaultUndoPathPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::vector< geometry_msgs::msg::PoseStamped > &plan)
nav_msgs::msg::Path lastForwardPathMsg_
void declareOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)