SMACC2
Loading...
Searching...
No Matches
forward_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 ******************************************************************************************************************/
23
24#include <angles/angles.h>
25#include <tf2/transform_datatypes.h>
26// #include <tf2/utils.h>
27
28#include <boost/assign.hpp>
29#include <boost/range/adaptor/reversed.hpp>
30#include <boost/range/algorithm/copy.hpp>
31#include <fstream>
32#include <nav_2d_utils/tf_help.hpp>
33#include <nav_msgs/msg/path.hpp>
34#include <pluginlib/class_list_macros.hpp>
35#include <rclcpp/rclcpp.hpp>
36#include <streambuf>
37
38namespace cl_nav2z
39{
40namespace forward_global_planner
41{
43// : nh_("~/ForwardGlobalPlanner")
44{
45 skip_straight_motion_distance_ = 0.2; // meters
46 puresSpinningRadStep_ = 1000; // rads
47}
48
50
52 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
53 const std::shared_ptr<tf2_ros::Buffer> tf,
54 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
55{
56 nh_ = parent.lock();
57 tf_ = tf;
58 name_ = name;
59 costmap_ros_ = costmap_ros;
60
61 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] initializing");
62 planPub_ = nh_->create_publisher<nav_msgs::msg::Path>("global_plan", rclcpp::QoS(1));
63 skip_straight_motion_distance_ = 0.2; // meters
64 puresSpinningRadStep_ = 1000; // rads
66}
67
69
70void ForwardGlobalPlanner::activate() { planPub_->on_activate(); }
71
73{
74 nav_msgs::msg::Path planMsg;
75 planPub_->publish(planMsg);
76 planPub_->on_deactivate();
77}
78
80 const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal)
81{
82 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] planning");
83
84 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
85
86 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] getting start and goal poses");
87 //---------------------------------------------------------------------
88 geometry_msgs::msg::PoseStamped transformedStart;
89 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
90 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
91 //---------------------------------------------------------------------
92 geometry_msgs::msg::PoseStamped transformedGoal;
93 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
94 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
95 //---------------------------------------------------------------------
96
97 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] creating plan vector");
98 nav_msgs::msg::Path planMsg;
99 std::vector<geometry_msgs::msg::PoseStamped> plan;
100
101 // three stages: 1 - heading to goal position, 2 - going forward keep orientation, 3 - heading to goal orientation
102
103 // 1 - heading to goal position
104 // orientation direction
105
106 double dx = transformedGoal.pose.position.x - transformedStart.pose.position.x;
107 double dy = transformedGoal.pose.position.y - transformedStart.pose.position.y;
108
109 double length = sqrt(dx * dx + dy * dy);
110
111 geometry_msgs::msg::PoseStamped prevState;
113 {
114 // skip initial pure spinning and initial straight motion
115 RCLCPP_INFO(nh_->get_logger(), "1 - heading to goal position pure spinning");
116 double heading_direction = atan2(dy, dx);
118 transformedStart, heading_direction, plan, puresSpinningRadStep_);
119
120 // RCLCPP_INFO(nh_->get_logger(), "2 - going forward keep orientation pure straight");
121 prevState =
122 cl_nav2z::makePureStraightSubPlan(prevState, transformedGoal.pose.position, length, plan);
123 }
124 else
125 {
126 prevState = transformedStart;
127 }
128
129 RCLCPP_INFO(nh_->get_logger(), "3 - heading to goal orientation");
130 double goalOrientation = angles::normalize_angle(tf2::getYaw(transformedGoal.pose.orientation));
131 cl_nav2z::makePureSpinningSubPlan(prevState, goalOrientation, plan, puresSpinningRadStep_);
132 planMsg.poses = plan;
133 planMsg.header.stamp = this->nh_->now();
134 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
135
136 RCLCPP_INFO_STREAM(
137 nh_->get_logger(), "[Forward Global Planner] generated plan size: " << plan.size());
138
139 // check plan rejection
140 bool acceptedGlobalPlan = true;
141
142 RCLCPP_INFO(
143 nh_->get_logger(), "[Forward Global Planner] checking obstacles in the generated plan");
144 nav2_costmap_2d::Costmap2D * costmap2d = this->costmap_ros_->getCostmap();
145 for (auto & p : plan)
146 {
147 unsigned int mx, my;
148 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
149 auto cost = costmap2d->getCost(mx, my);
150
151 // static const unsigned char NO_INFORMATION = 255;
152 // static const unsigned char LETHAL_OBSTACLE = 254;
153 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
154 // static const unsigned char FREE_SPACE = 0;
155
156 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
157 {
158 RCLCPP_INFO_STREAM(
159 nh_->get_logger(), "[Forward Global Planner] pose " << p.pose.position.x << ", "
160 << p.pose.position.y
161 << " rejected, cost: " << cost);
162 acceptedGlobalPlan = false;
163 break;
164 }
165 }
166
167 if (acceptedGlobalPlan)
168 {
169 RCLCPP_INFO_STREAM(
170 nh_->get_logger(), "[Forward Global Planner] accepted plan: " << plan.size());
171 planPub_->publish(planMsg);
172 return planMsg;
173 }
174 else
175 {
176 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] plan rejected");
177 planMsg.poses.clear();
178 planPub_->publish(planMsg);
179 return planMsg;
180 }
181}
182
183} // namespace forward_global_planner
184} // namespace cl_nav2z
185
186// register this planner as a BaseGlobalPlanner plugin
187PLUGINLIB_EXPORT_CLASS(
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
virtual void cleanup()
Method to cleanup resources used on shutdown.
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.
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
virtual void activate()
Method to active planner and any threads involved in execution.
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