Skip to content

Commit

Permalink
review and format a_star, d_star, d_star_lite, lpa_star
Browse files Browse the repository at this point in the history
  • Loading branch information
ZhanyuGuo committed Aug 23, 2024
1 parent a91df4d commit da08397
Show file tree
Hide file tree
Showing 10 changed files with 134 additions and 180 deletions.
10 changes: 5 additions & 5 deletions src/core/global_planner/global_planner/include/global_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class GlobalPlanner
public:
/**
* @brief Construct a new Global Planner object
* @param costmap the environment for path planning
* @param costmap the environment for path planning
*/
GlobalPlanner(costmap_2d::Costmap2D* costmap);

Expand All @@ -46,10 +46,10 @@ class GlobalPlanner

/**
* @brief Pure virtual function that is overloadde by planner implementations
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @return true if path found, else false
*/
virtual bool plan(const Node& start, const Node& goal, std::vector<Node>& path, std::vector<Node>& expand) = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ namespace global_planner
{
/**
* @brief Construct a new Global Planner object
* @param costmap the environment for path planning
* @param costmap the environment for path planning
*/
GlobalPlanner::GlobalPlanner(costmap_2d::Costmap2D* costmap) : factor_(0.5f), map_size_{ 0 }
{
Expand Down
14 changes: 7 additions & 7 deletions src/core/global_planner/graph_planner/include/a_star.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,18 +29,18 @@ class AStar : public GlobalPlanner
public:
/**
* @brief Construct a new AStar object
* @param costmap the environment for path planning
* @param dijkstra using diksktra implementation
* @param gbfs using gbfs implementation
* @param costmap the environment for path planning
* @param dijkstra using diksktra implementation
* @param gbfs using gbfs implementation
*/
AStar(costmap_2d::Costmap2D* costmap, bool dijkstra = false, bool gbfs = false);

/**
* @brief A* implementation
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @return true if path found, else false
*/
bool plan(const Node& start, const Node& goal, std::vector<Node>& path, std::vector<Node>& expand);
Expand Down
8 changes: 1 addition & 7 deletions src/core/global_planner/graph_planner/include/d_star.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,8 @@
#ifndef D_STAR_H
#define D_STAR_H

#include <map>

#include <ros/ros.h>

#include "global_planner.h"

#define WINDOW_SIZE 70 // local costmap window size (in grid, 3.5m / 0.05 = 70)

namespace global_planner
{
typedef DNode* DNodePtr;
Expand All @@ -37,7 +31,7 @@ class DStar : public GlobalPlanner
public:
/**
* @brief Construct a new DStar object
* @param costmap the environment for path planning
* @param costmap the environment for path planning
*/
DStar(costmap_2d::Costmap2D* costmap);

Expand Down
42 changes: 10 additions & 32 deletions src/core/global_planner/graph_planner/include/d_star_lite.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,8 @@
#ifndef D_STAR_LITE_H
#define D_STAR_LITE_H

#include <ros/ros.h>

#include <map>
#include <algorithm>

#include "global_planner.h"

#define WINDOW_SIZE 70 // local costmap window size (in grid, 3.5m / 0.05 = 70)

namespace global_planner
{
typedef LNode* LNodePtr;
Expand All @@ -38,7 +31,7 @@ class DStarLite : public GlobalPlanner
public:
/**
* @brief Construct a new DStarLite object
* @param costmap the environment for path planning
* @param costmap the environment for path planning
*/
DStarLite(costmap_2d::Costmap2D* costmap);

Expand All @@ -54,41 +47,36 @@ class DStarLite : public GlobalPlanner

/**
* @brief Get heuristics between n1 and n2
*
* @param n1 LNode pointer of on LNode
* @param n2 LNode pointer of the other LNode
* @param n1 LNode pointer of on LNode
* @param n2 LNode pointer of the other LNode
* @return heuristics between n1 and n2
*/
double getH(LNodePtr n1, LNodePtr n2);

/**
* @brief Calculate the key of s
*
* @param s LNode pointer
* @return the key value
*/
double calculateKey(LNodePtr s);

/**
* @brief Check if there is collision between n1 and n2
*
* @param n1 DNode pointer of one DNode
* @param n2 DNode pointer of the other DNode
* @param n1 LNode pointer of one LNode
* @param n2 LNode pointer of the other LNode
* @return true if collision, else false
*/
bool isCollision(LNodePtr n1, LNodePtr n2);

/**
* @brief Get neighbour LNodePtrs of nodePtr
*
* @param node_ptr DNode to expand
* @param neighbours neigbour LNodePtrs in vector
* @param node_ptr LNode to expand
* @param neighbours neigbour LNodePtrs in vector
*/
void getNeighbours(LNodePtr u, std::vector<LNodePtr>& neighbours);

/**
* @brief Get the cost between n1 and n2, return INF if collision
*
* @param n1 LNode pointer of one LNode
* @param n2 LNode pointer of the other LNode
* @return cost between n1 and n2
Expand All @@ -97,7 +85,6 @@ class DStarLite : public GlobalPlanner

/**
* @brief Update vertex u
*
* @param u LNode pointer to update
*/
void updateVertex(LNodePtr u);
Expand All @@ -109,26 +96,17 @@ class DStarLite : public GlobalPlanner

/**
* @brief Extract path for map
*
* @param start start node
* @param goal goal node
* @return flag true if extract successfully else do not
*/
bool extractPath(const Node& start, const Node& goal);

/**
* @brief Get the closest Node of the path to current state
*
* @param current current state
* @return the closest Node
*/
Node getState(const Node& current);

/**
* @brief D* lite implementation
* @param start start node
* @param goal goal node
* @param expand containing the node been search during the process
* @param start start node
* @param goal goal node
* @param expand containing the node been search during the process
* @return tuple contatining a bool as to whether a path was found, and the path
*/
bool plan(const Node& start, const Node& goal, std::vector<Node>& path, std::vector<Node>& expand);
Expand Down
16 changes: 4 additions & 12 deletions src/core/global_planner/graph_planner/include/lpa_star.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,29 +17,21 @@
#ifndef LPA_STAR_H
#define LPA_STAR_H

#include <ros/ros.h>

#include <map>
#include <algorithm>

#include "global_planner.h"

#define WINDOW_SIZE 70 // local costmap window size (in grid, 3.5m / 0.05 = 70)

namespace global_planner
{
typedef LNode* LNodePtr;

/**
* @brief Class for objects that plan using the LPA* algorithm
* @param costmap the environment for path planning
*/
class LPAStar : public GlobalPlanner
{
public:
/**
* @brief Construct a new LPAStar object
* @param costmap the environment for path planning
* @param costmap the environment for path planning
*/
LPAStar(costmap_2d::Costmap2D* costmap);

Expand Down Expand Up @@ -70,15 +62,15 @@ class LPAStar : public GlobalPlanner

/**
* @brief Check if there is collision between n1 and n2
* @param n1 DNode pointer of one DNode
* @param n2 DNode pointer of the other DNode
* @param n1 LNode pointer of one LNode
* @param n2 LNode pointer of the other LNode
* @return true if collision, else false
*/
bool isCollision(LNodePtr n1, LNodePtr n2);

/**
* @brief Get neighbour LNodePtrs of nodePtr
* @param node_ptr DNode to expand
* @param node_ptr LNode to expand
* @param neighbours neigbour LNodePtrs in vector
*/
void getNeighbours(LNodePtr u, std::vector<LNodePtr>& neighbours);
Expand Down
14 changes: 7 additions & 7 deletions src/core/global_planner/graph_planner/src/a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ namespace global_planner
{
/**
* @brief Construct a new AStar object
* @param costmap the environment for path planning
* @param dijkstra using diksktra implementation
* @param gbfs using gbfs implementation
* @param costmap the environment for path planning
* @param dijkstra using diksktra implementation
* @param gbfs using gbfs implementation
*/
AStar::AStar(costmap_2d::Costmap2D* costmap, bool dijkstra, bool gbfs) : GlobalPlanner(costmap)
{
Expand All @@ -45,10 +45,10 @@ AStar::AStar(costmap_2d::Costmap2D* costmap, bool dijkstra, bool gbfs) : GlobalP

/**
* @brief A* implementation
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @param start start node
* @param goal goal node
* @param path optimal path consists of Node
* @param expand containing the node been search during the process
* @return true if path found, else false
*/
bool AStar::plan(const Node& start, const Node& goal, std::vector<Node>& path, std::vector<Node>& expand)
Expand Down
Loading

0 comments on commit da08397

Please sign in to comment.