SMACC2
Loading...
Searching...
No Matches
backward_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
23
24#include <angles/angles.h>
25#include <tf2/transform_datatypes.h>
27#include <nav_msgs/msg/path.hpp>
28#include <visualization_msgs/msg/marker_array.hpp>
29
30#include <tf2/utils.h>
31#include <boost/assign.hpp>
32#include <boost/range/adaptor/reversed.hpp>
33#include <boost/range/algorithm/copy.hpp>
34#include <fstream>
35#include <nav_2d_utils/tf_help.hpp>
36#include <pluginlib/class_list_macros.hpp>
37#include <streambuf>
38
39using namespace std::chrono_literals;
40namespace cl_nav2z
41{
42namespace backward_global_planner
43{
50{
52 puresSpinningRadStep_ = 1000; // rads
53}
54
56
63 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
64 std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
65{
66 this->nh_ = parent.lock();
67 name_ = name;
68 tf_ = tf;
70
71 // RCLCPP_INFO_NAMED(nh_->get_logger(), "Backwards", "BackwardGlobalPlanner initialize");
72 costmap_ros_ = costmap_ros;
73 // RCLCPP_WARN_NAMED(nh_->get_logger(), "Backwards", "Initializing global planner, costmap address: %ld",
74 // (long)costmap_ros);
75
76 planPub_ = nh_->create_publisher<nav_msgs::msg::Path>("backward_planner/global_plan", 1);
78 nh_->create_publisher<visualization_msgs::msg::MarkerArray>("backward_planner/markers", 1);
79
80 declareOrSet(nh_, name_ + ".transform_tolerance", transform_tolerance_);
81}
82
89
96{
97 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardGlobalPlanner] activating planner");
98 planPub_->on_activate();
99 markersPub_->on_activate();
100}
101
108{
109 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardGlobalPlanner] deactivating planner");
110
111 // clear
112 nav_msgs::msg::Path planMsg;
113 planMsg.header.stamp = nh_->now();
114 planPub_->publish(planMsg);
115
116 planPub_->on_deactivate();
117 this->cleanMarkers();
118 markersPub_->on_deactivate();
119}
120
127 const geometry_msgs::msg::Pose & pose, double r, double g, double b)
128{
129 double phi = tf2::getYaw(pose.orientation);
130 visualization_msgs::msg::Marker marker;
131 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
132 marker.header.stamp = nh_->now();
133 marker.ns = "my_namespace2";
134 marker.id = 0;
135 marker.type = visualization_msgs::msg::Marker::ARROW;
136 marker.action = visualization_msgs::msg::Marker::ADD;
137 marker.lifetime = rclcpp::Duration(0s);
138 marker.scale.x = 0.1;
139 marker.scale.y = 0.3;
140 marker.scale.z = 0.1;
141 marker.color.a = 1.0;
142 marker.color.r = r;
143 marker.color.g = g;
144 marker.color.b = b;
145
146 geometry_msgs::msg::Point start, end;
147 start.x = pose.position.x;
148 start.y = pose.position.y;
149
150 end.x = pose.position.x + 0.5 * cos(phi);
151 end.y = pose.position.y + 0.5 * sin(phi);
152
153 marker.points.push_back(start);
154 marker.points.push_back(end);
155
156 visualization_msgs::msg::MarkerArray ma;
157 ma.markers.push_back(marker);
158
159 markersPub_->publish(ma);
160}
161
163{
164 visualization_msgs::msg::Marker marker;
165 marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();
166 marker.header.stamp = nh_->now();
167 marker.ns = "my_namespace2";
168 marker.id = 0;
169 marker.action = visualization_msgs::msg::Marker::DELETEALL;
170
171 visualization_msgs::msg::MarkerArray ma;
172 ma.markers.push_back(marker);
173
174 markersPub_->publish(ma);
175}
176
183 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal,
184 std::vector<geometry_msgs::msg::PoseStamped> & plan)
185{
186 auto q = start.pose.orientation;
187
188 geometry_msgs::msg::PoseStamped pose;
189 pose = start;
190
191 double dx = start.pose.position.x - goal.pose.position.x;
192 double dy = start.pose.position.y - goal.pose.position.y;
193
194 double length = sqrt(dx * dx + dy * dy);
195
196 geometry_msgs::msg::PoseStamped prevState;
198 {
199 // skip initial pure spinning and initial straight motion
200 RCLCPP_INFO(
201 nh_->get_logger(), "1 - heading to goal position pure spinning radstep: %lf",
203 double heading_direction = atan2(dy, dx);
204 double startyaw = tf2::getYaw(q);
205 double offset = angles::shortest_angular_distance(startyaw, heading_direction);
206 heading_direction = startyaw + offset;
207
208 prevState =
209 cl_nav2z::makePureSpinningSubPlan(start, heading_direction, plan, puresSpinningRadStep_);
210 RCLCPP_INFO(nh_->get_logger(), "2 - going forward keep orientation pure straight");
211
212 prevState = cl_nav2z::makePureStraightSubPlan(prevState, goal.pose.position, length, plan);
213 }
214 else
215 {
216 prevState = start;
217 }
218
219 RCLCPP_WARN_STREAM(
220 nh_->get_logger(), "[BackwardGlobalPlanner] backward global plan size: " << plan.size());
221}
222
229 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal)
230{
231 RCLCPP_INFO_STREAM(
232 nh_->get_logger(), "[BackwardGlobalPlanner] goal frame id: "
233 << goal.header.frame_id << " pose: " << goal.pose.position);
234 RCLCPP_INFO_STREAM(
235 nh_->get_logger(), "[BackwardGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
236
237 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
238 //---------------------------------------------------------------------
239 geometry_msgs::msg::PoseStamped transformedStart;
240 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
241 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
242 //---------------------------------------------------------------------
243 geometry_msgs::msg::PoseStamped transformedGoal;
244 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
245 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
246
247 RCLCPP_INFO_STREAM(
248 nh_->get_logger(), "[BackwardGlobalPlanner] creating default backward global plan");
249 //---------------------------------------------------------------------
250 std::vector<geometry_msgs::msg::PoseStamped> plan;
251 this->createDefaultBackwardPath(transformedStart, transformedGoal, plan);
252
253 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardGlobalPlanner] publishing markers");
254 publishGoalMarker(transformedGoal.pose, 1.0, 0, 1.0);
255
256 nav_msgs::msg::Path planMsg;
257 planMsg.poses = plan;
258 planMsg.header.stamp = this->nh_->now();
259 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
260
261 //---------------------------------------------------------------------
262 // check plan rejection if obstacle is found
263 bool acceptedGlobalPlan = true;
264
265 RCLCPP_INFO_STREAM(
266 nh_->get_logger(), "[BackwardGlobalPlanner] checking backwards trajectory on costmap");
267 auto costmap2d = this->costmap_ros_->getCostmap();
268 for (auto & p : plan)
269 {
270 uint32_t mx, my;
271 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
272 auto cost = costmap2d->getCost(mx, my);
273
274 // static const unsigned char NO_INFORMATION = 255;
275 // static const unsigned char LETHAL_OBSTACLE = 254;
276 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
277 // static const unsigned char FREE_SPACE = 0;
278 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
279 {
280 RCLCPP_WARN_STREAM(
281 nh_->get_logger(),
282 "[BackwardGlobalPlanner] backwards plan is rejected because interscts the obstacle "
283 "inscribed inflated obstacle"
284 << " at: " << p.pose.position.x << " " << p.pose.position.y);
285
286 break;
287 }
288 }
289
290 if (!acceptedGlobalPlan)
291 {
292 RCLCPP_WARN_STREAM(
293 nh_->get_logger(),
294 "[BackwardGlobalPlanner] backward plan request is not accepted, returning "
295 "empty path");
296 planMsg.poses.clear();
297 }
298
299 RCLCPP_WARN_STREAM(
300 nh_->get_logger(), "[BackwardGlobalPlanner] backward global plan publishing path. poses count: "
301 << planMsg.poses.size());
302 planPub_->publish(planMsg);
303
304 return planMsg;
305}
306
307} // namespace backward_global_planner
308} // namespace cl_nav2z
309
310// register this planner as a BaseGlobalPlanner plugin
311PLUGINLIB_EXPORT_CLASS(
virtual void activate()
Method to active planner and any threads involved in execution.
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.
void publishGoalMarker(const geometry_msgs::msg::Pose &pose, double r, double g, double b)
virtual void cleanup()
Method to cleanup resources used on shutdown.
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
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)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > markersPub_
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
void createDefaultBackwardPath(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
geometry_msgs::msg::PoseStamped makePureSpinningSubPlan(const geometry_msgs::msg::PoseStamped &start, double dstRads, std::vector< geometry_msgs::msg::PoseStamped > &plan, double radstep=0.005)
Definition: common.cpp:37
geometry_msgs::msg::PoseStamped makePureStraightSubPlan(const geometry_msgs::msg::PoseStamped &startOrientedPose, const geometry_msgs::msg::Point &goal, double length, std::vector< geometry_msgs::msg::PoseStamped > &plan)
Definition: common.cpp:93