SMACC2
Loading...
Searching...
No Matches
forward_global_planner.cpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft 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 std::function<bool()> /*cancel_checker*/)
82{
83 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] planning");
84
85 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
86
87 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] getting start and goal poses");
88 //---------------------------------------------------------------------
89 geometry_msgs::msg::PoseStamped transformedStart;
90 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
91 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
92 //---------------------------------------------------------------------
93 geometry_msgs::msg::PoseStamped transformedGoal;
94 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
95 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
96 //---------------------------------------------------------------------
97
98 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] creating plan vector");
99 nav_msgs::msg::Path planMsg;
100 std::vector<geometry_msgs::msg::PoseStamped> plan;
101
102 // three stages: 1 - heading to goal position, 2 - going forward keep orientation, 3 - heading to goal orientation
103
104 // 1 - heading to goal position
105 // orientation direction
106
107 double dx = transformedGoal.pose.position.x - transformedStart.pose.position.x;
108 double dy = transformedGoal.pose.position.y - transformedStart.pose.position.y;
109
110 double length = sqrt(dx * dx + dy * dy);
111
112 geometry_msgs::msg::PoseStamped prevState;
114 {
115 // skip initial pure spinning and initial straight motion
116 RCLCPP_INFO(nh_->get_logger(), "1 - heading to goal position pure spinning");
117 double heading_direction = atan2(dy, dx);
119 transformedStart, heading_direction, plan, puresSpinningRadStep_);
120
121 // RCLCPP_INFO(nh_->get_logger(), "2 - going forward keep orientation pure straight");
122 prevState =
123 cl_nav2z::makePureStraightSubPlan(prevState, transformedGoal.pose.position, length, plan);
124 }
125 else
126 {
127 prevState = transformedStart;
128 }
129
130 RCLCPP_INFO(nh_->get_logger(), "3 - heading to goal orientation");
131 double goalOrientation = angles::normalize_angle(tf2::getYaw(transformedGoal.pose.orientation));
132 cl_nav2z::makePureSpinningSubPlan(prevState, goalOrientation, plan, puresSpinningRadStep_);
133 planMsg.poses = plan;
134 planMsg.header.stamp = this->nh_->now();
135 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
136
137 RCLCPP_INFO_STREAM(
138 nh_->get_logger(), "[Forward Global Planner] generated plan size: " << plan.size());
139
140 // check plan rejection
141 bool acceptedGlobalPlan = true;
142
143 RCLCPP_INFO(
144 nh_->get_logger(), "[Forward Global Planner] checking obstacles in the generated plan");
145 nav2_costmap_2d::Costmap2D * costmap2d = this->costmap_ros_->getCostmap();
146 for (auto & p : plan)
147 {
148 unsigned int mx, my;
149 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
150 auto cost = costmap2d->getCost(mx, my);
151
152 // static const unsigned char NO_INFORMATION = 255;
153 // static const unsigned char LETHAL_OBSTACLE = 254;
154 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
155 // static const unsigned char FREE_SPACE = 0;
156
157 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
158 {
159 RCLCPP_INFO_STREAM(
160 nh_->get_logger(), "[Forward Global Planner] pose " << p.pose.position.x << ", "
161 << p.pose.position.y
162 << " rejected, cost: " << cost);
163 acceptedGlobalPlan = false;
164 break;
165 }
166 }
167
168 if (acceptedGlobalPlan)
169 {
170 RCLCPP_INFO_STREAM(
171 nh_->get_logger(), "[Forward Global Planner] accepted plan: " << plan.size());
172 planPub_->publish(planMsg);
173 return planMsg;
174 }
175 else
176 {
177 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] plan rejected");
178 planMsg.poses.clear();
179 planPub_->publish(planMsg);
180 return planMsg;
181 }
182}
183
184} // namespace forward_global_planner
185} // namespace cl_nav2z
186
187// register this planner as a BaseGlobalPlanner plugin
188PLUGINLIB_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, std::function< bool()> cancel_checker) override
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