18 #include "nav2_theta_star_planner/theta_star_planner.hpp"
19 #include "nav2_theta_star_planner/theta_star.hpp"
21 namespace nav2_theta_star_planner
24 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
25 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
26 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
28 planner_ = std::make_unique<theta_star::ThetaStar>();
29 parent_node_ = parent;
30 auto node = parent_node_.lock();
31 logger_ = node->get_logger();
32 clock_ = node->get_clock();
35 planner_->costmap_ = costmap_ros->getCostmap();
36 global_frame_ = costmap_ros->getGlobalFrameID();
38 nav2_util::declare_parameter_if_not_declared(
39 node, name_ +
".how_many_corners", rclcpp::ParameterValue(8));
41 node->get_parameter(name_ +
".how_many_corners", planner_->how_many_corners_);
43 if (planner_->how_many_corners_ != 8 && planner_->how_many_corners_ != 4) {
44 planner_->how_many_corners_ = 8;
45 RCLCPP_WARN(logger_,
"Your value for - .how_many_corners was overridden, and is now set to 8");
48 nav2_util::declare_parameter_if_not_declared(
49 node, name_ +
".allow_unknown", rclcpp::ParameterValue(
true));
50 node->get_parameter(name_ +
".allow_unknown", planner_->allow_unknown_);
52 nav2_util::declare_parameter_if_not_declared(
53 node, name_ +
".w_euc_cost", rclcpp::ParameterValue(1.0));
54 node->get_parameter(name_ +
".w_euc_cost", planner_->w_euc_cost_);
56 nav2_util::declare_parameter_if_not_declared(
57 node, name_ +
".w_traversal_cost", rclcpp::ParameterValue(2.0));
58 node->get_parameter(name_ +
".w_traversal_cost", planner_->w_traversal_cost_);
60 planner_->w_heuristic_cost_ = planner_->w_euc_cost_ < 1.0 ? planner_->w_euc_cost_ : 1.0;
62 nav2_util::declare_parameter_if_not_declared(
63 node, name +
".use_final_approach_orientation", rclcpp::ParameterValue(
false));
64 node->get_parameter(name +
".use_final_approach_orientation", use_final_approach_orientation_);
69 RCLCPP_INFO(logger_,
"CleaningUp plugin %s of type nav2_theta_star_planner", name_.c_str());
75 RCLCPP_INFO(logger_,
"Activating plugin %s of type nav2_theta_star_planner", name_.c_str());
77 auto node = parent_node_.lock();
78 dyn_params_handler_ = node->add_on_set_parameters_callback(
84 RCLCPP_INFO(logger_,
"Deactivating plugin %s of type nav2_theta_star_planner", name_.c_str());
88 const geometry_msgs::msg::PoseStamped & start,
89 const geometry_msgs::msg::PoseStamped & goal)
91 nav_msgs::msg::Path global_path;
92 auto start_time = std::chrono::steady_clock::now();
94 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(planner_->costmap_->getMutex()));
97 unsigned int mx_start, my_start, mx_goal, my_goal;
98 if (!planner_->costmap_->worldToMap(
99 start.pose.position.x, start.pose.position.y, mx_start, my_start))
101 RCLCPP_WARN(logger_,
"Start Coordinates were outside map bounds");
105 if (!planner_->costmap_->worldToMap(
106 goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal))
108 RCLCPP_WARN(logger_,
"Goal Coordinates were outside map bounds");
112 if (mx_start == mx_goal && my_start == my_goal) {
113 if (planner_->costmap_->getCost(mx_start, my_start) == nav2_costmap_2d::LETHAL_OBSTACLE) {
114 RCLCPP_WARN(logger_,
"Failed to create a unique pose path because of obstacles");
117 global_path.header.stamp = clock_->now();
118 global_path.header.frame_id = global_frame_;
119 geometry_msgs::msg::PoseStamped pose;
120 pose.header = global_path.header;
121 pose.pose.position.z = 0.0;
123 pose.pose = start.pose;
127 if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
128 pose.pose.orientation = goal.pose.orientation;
130 global_path.poses.push_back(pose);
134 planner_->setStartAndGoal(start, goal);
136 logger_,
"Got the src and dst... (%i, %i) && (%i, %i)",
137 planner_->src_.x, planner_->src_.y, planner_->dst_.x, planner_->dst_.y);
140 size_t plan_size = global_path.poses.size();
142 global_path.poses.back().pose.orientation = goal.pose.orientation;
149 if (use_final_approach_orientation_) {
150 if (plan_size == 1) {
151 global_path.poses.back().pose.orientation = start.pose.orientation;
152 }
else if (plan_size > 1) {
153 double dx, dy, theta;
154 auto last_pose = global_path.poses.back().pose.position;
155 auto approach_pose = global_path.poses[plan_size - 2].pose.position;
156 dx = last_pose.x - approach_pose.x;
157 dy = last_pose.y - approach_pose.y;
158 theta = atan2(dy, dx);
159 global_path.poses.back().pose.orientation =
160 nav2_util::geometry_utils::orientationAroundZAxis(theta);
164 auto stop_time = std::chrono::steady_clock::now();
165 auto dur = std::chrono::duration_cast<std::chrono::microseconds>(stop_time - start_time);
166 RCLCPP_DEBUG(logger_,
"the time taken is : %i",
static_cast<int>(dur.count()));
167 RCLCPP_DEBUG(logger_,
"the nodes_opened are: %i", planner_->nodes_opened);
173 std::vector<coordsW> path;
174 if (planner_->isUnsafeToPlan()) {
175 RCLCPP_ERROR(logger_,
"Either of the start or goal pose are an obstacle! ");
176 global_path.poses.clear();
177 }
else if (planner_->generatePath(path)) {
180 RCLCPP_ERROR(logger_,
"Could not generate path between the given poses");
181 global_path.poses.clear();
183 global_path.header.stamp = clock_->now();
184 global_path.header.frame_id = global_frame_;
188 const std::vector<coordsW> & raw_path,
189 const double & dist_bw_points)
191 nav_msgs::msg::Path pa;
193 geometry_msgs::msg::PoseStamped p1;
194 for (
unsigned int j = 0; j < raw_path.size() - 1; j++) {
196 p1.pose.position.x = pt1.x;
197 p1.pose.position.y = pt1.y;
198 pa.poses.push_back(p1);
201 double distance = std::hypot(pt2.x - pt1.x, pt2.y - pt1.y);
202 int loops =
static_cast<int>(distance / dist_bw_points);
203 double sin_alpha = (pt2.y - pt1.y) / distance;
204 double cos_alpha = (pt2.x - pt1.x) / distance;
205 for (
int k = 1; k < loops; k++) {
206 p1.pose.position.x = pt1.x + k * dist_bw_points * cos_alpha;
207 p1.pose.position.y = pt1.y + k * dist_bw_points * sin_alpha;
208 pa.poses.push_back(p1);
215 rcl_interfaces::msg::SetParametersResult
218 rcl_interfaces::msg::SetParametersResult result;
219 for (
auto parameter : parameters) {
220 const auto & type = parameter.get_type();
221 const auto & name = parameter.get_name();
223 if (type == ParameterType::PARAMETER_INTEGER) {
224 if (name == name_ +
".how_many_corners") {
225 planner_->how_many_corners_ = parameter.as_int();
227 }
else if (type == ParameterType::PARAMETER_DOUBLE) {
228 if (name == name_ +
".w_euc_cost") {
229 planner_->w_euc_cost_ = parameter.as_double();
230 }
else if (name == name_ +
".w_traversal_cost") {
231 planner_->w_traversal_cost_ = parameter.as_double();
233 }
else if (type == ParameterType::PARAMETER_BOOL) {
234 if (name == name_ +
".use_final_approach_orientation") {
235 use_final_approach_orientation_ = parameter.as_bool();
236 }
else if (name == name_ +
".allow_unknown") {
237 planner_->allow_unknown_ = parameter.as_bool();
242 result.successful =
true;
248 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
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) override
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Method create the plan from a starting and ending goal.
void cleanup() override
Method to cleanup resources used on shutdown.
static nav_msgs::msg::Path linearInterpolation(const std::vector< coordsW > &raw_path, const double &dist_bw_points)
interpolates points between the consecutive waypoints of the path
void deactivate() override
Method to deactive planner and any threads involved in execution.
void getPlan(nav_msgs::msg::Path &global_path)
the function responsible for calling the algorithm and retrieving a path from it
void activate() override
Method to active planner and any threads involved in execution.