15 #ifndef NAV2_THETA_STAR_PLANNER__THETA_STAR_HPP_
16 #define NAV2_THETA_STAR_PLANNER__THETA_STAR_HPP_
23 #include "rclcpp/rclcpp.hpp"
24 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
26 const double INF_COST = DBL_MAX;
27 const int UNKNOWN_COST = 255;
28 const int OBS_COST = 254;
29 const int LETHAL_COST = 252;
47 bool is_in_queue =
false;
55 return (p1->f) > (p2->f);
96 inline bool isSafe(
const int & cx,
const int & cy)
const
107 const geometry_msgs::msg::PoseStamped & start,
108 const geometry_msgs::msg::PoseStamped & goal);
116 return !(
isSafe(src_.x, src_.y)) || !(
isSafe(dst_.x, dst_.y));
119 int nodes_opened = 0;
135 std::priority_queue<tree_node *, std::vector<tree_node *>,
comp>
queue_;
142 const coordsM moves[8] = {{0, 1},
176 const int & x0,
const int & y0,
const int & x1,
const int & y1,
177 double & sl_cost)
const;
191 bool isSafe(
const int & cx,
const int & cy,
double & cost)
const
193 double curr_cost = getCost(cx, cy);
195 if (costmap_->
getCost(cx, cy) == UNKNOWN_COST) {
196 curr_cost = OBS_COST - 1;
209 inline double getCost(
const int & cx,
const int & cy)
const
211 return 26 + 0.9 * costmap_->
getCost(cx, cy);
221 double curr_cost = getCost(cx, cy);
230 inline double getEuclideanCost(
const int & ax,
const int & ay,
const int & bx,
const int & by)
240 inline double getHCost(
const int & cx,
const int & cy)
251 return cx >= 0 && cx < size_x_ && cy >= 0 && cy < size_y_;
260 return this_node.x == dst_.x && this_node.y == dst_.y;
293 if (
static_cast<int>(
nodes_data_.size()) <= id_this) {
310 queue_ = std::priority_queue<tree_node *, std::vector<tree_node *>,
comp>();
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
std::vector< tree_node * > node_position_
void addIndex(const int &cx, const int &cy, tree_node *node_this)
it stores id_this in node_position_ at the index [ size_x_*cy + cx ]
double w_euc_cost_
weight on the euclidean distance cost (used for calculations of g_cost)
double w_heuristic_cost_
weight on the heuristic cost (used for h_cost calculations)
int how_many_corners_
parameter to set the number of adjacent nodes to be searched on
int size_x_
the x-directional and y-directional lengths of the map respectively
bool generatePath(std::vector< coordsW > &raw_path)
it iteratively searches upon the nodes in the queue (open list) until the current node is the goal po...
bool losCheck(const int &x0, const int &y0, const int &x1, const int &y1, double &sl_cost) const
performs the line of sight check using Bresenham's Algorithm, and has been modified to calculate the ...
bool isGoal(const tree_node &this_node) const
checks if the coordinates of a node is the goal or not
void backtrace(std::vector< coordsW > &raw_points, const tree_node *curr_n) const
it returns the path by backtracking from the goal to the start, by using their parent nodes
bool withinLimits(const int &cx, const int &cy) const
checks if the given coordinates(cx, cy) lies within the map
double getEuclideanCost(const int &ax, const int &ay, const int &bx, const int &by)
calculates the piecewise straight line euclidean distances by <euc_cost_parameter>*<euclidean distanc...
bool isUnsafeToPlan() const
checks whether the start and goal points have costmap costs greater than LETHAL_COST
std::priority_queue< tree_node *, std::vector< tree_node * >, comp > queue_
this is the priority queue (open_list) to select the next node to be expanded
void initializePosn(int size_inc=0)
initialises the node_position_ vector by storing -1 as index for all points(x, y) within the limits o...
bool allow_unknown_
parameter to set weather the planner can plan through unknown space
void setNeighbors(const tree_node *curr_data)
this function expands the current node
tree_node * getIndex(const int &cx, const int &cy)
retrieves the pointer of the location at which the data of the point(cx, cy) is stored in nodes_data
bool isSafe(const int &cx, const int &cy) const
this function checks whether the cost of a point(cx, cy) on the costmap is less than the LETHAL_COST
double w_traversal_cost_
weight on the costmap traversal cost
void setStartAndGoal(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)
initialises the values of the start and goal points
std::vector< tree_node > nodes_data_
double getHCost(const int &cx, const int &cy)
for the point(cx, cy), its heuristic cost is calculated by <heuristic_cost_parameter>*<euclidean dist...
double getTraversalCost(const int &cx, const int &cy)
for the point(cx, cy), its traversal cost is calculated by <parameter>*(<actual_traversal_cost_from_c...
void resetParent(tree_node *curr_data)
it performs a line of sight (los) check between the current node and the parent node of its parent no...
void addToNodesData(const int &id_this)
this function depending on the size of the nodes_data_ vector allots space to store the data for a no...
void clearQueue()
clears the priority queue after each execution of the generatePath function
void resetContainers()
initialises the values of global variables at beginning of the execution of the generatePath function
bool isSafe(const int &cx, const int &cy, double &cost) const
it is an overloaded function to ease the cost calculations while performing the LOS check