Skip to content

Commit

Permalink
semantic planners added
Browse files Browse the repository at this point in the history
  • Loading branch information
jcobano committed Jul 24, 2024
1 parent 52fbe40 commit 4dfadb0
Show file tree
Hide file tree
Showing 16 changed files with 2,083 additions and 4 deletions.
12 changes: 9 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ generate_messages(
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES AlgorithmBase AStar AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF
LIBRARIES AlgorithmBase AStar AStarSemantic AStarSemanticCost AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarSemantic ThetaStarSemanticCost ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarSemantic LazyThetaStarSemanticCost LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF
#
CATKIN_DEPENDS std_msgs visualization_msgs geometry_msgs nav_msgs roscpp message_runtime costmap_2d grid_message
# DEPENDS system_lib
Expand Down Expand Up @@ -156,12 +156,18 @@ add_library(AStar src/Planners/AStar.cpp

add_library(AStar_Gradient src/Planners/AStar_Gradient.cpp )
add_library(AStar_EDF src/Planners/AStar_EDF.cpp )
add_library(AStarSemantic src/Planners/AStarSemantic.cpp )
add_library(AStarSemanticCost src/Planners/AStarSemanticCost.cpp )
add_library(AStarM1 src/Planners/AStarM1.cpp )
add_library(AStarM2 src/Planners/AStarM2.cpp )
add_library(ThetaStar src/Planners/ThetaStar.cpp )
add_library(ThetaStarSemantic src/Planners/ThetaStarSemantic.cpp )
add_library(ThetaStarSemanticCost src/Planners/ThetaStarSemanticCost.cpp )
add_library(ThetaStarM1 src/Planners/ThetaStarM1.cpp )
add_library(ThetaStarM2 src/Planners/ThetaStarM2.cpp )
add_library(LazyThetaStar src/Planners/LazyThetaStar.cpp )
add_library(LazyThetaStarSemantic src/Planners/LazyThetaStarSemantic.cpp )
add_library(LazyThetaStarSemanticCost src/Planners/LazyThetaStarSemanticCost.cpp )
add_library(LazyThetaStarM1 src/Planners/LazyThetaStarM1.cpp )
add_library(LazyThetaStarM1Mod src/Planners/LazyThetaStarM1Mod.cpp )
add_library(LazyThetaStarM2 src/Planners/LazyThetaStarM2.cpp )
Expand All @@ -170,7 +176,7 @@ add_library(LazyThetaStar_EDF src/Planners/LazyThetaStar_EDF.cpp )



list(APPEND ${PROJECT_NAME}_LIBRARIES AlgorithmBase AStar AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF)
list(APPEND ${PROJECT_NAME}_LIBRARIES AlgorithmBase AStar AStarSemantic AStarSemanticCost AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarSemantic ThetaStarSemanticCost ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarSemantic LazyThetaStarSemanticCost LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF)
target_link_libraries(${${PROJECT_NAME}_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
add_dependencies( ${${PROJECT_NAME}_LIBRARIES} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
list(APPEND ${PROJECT_NAME}_TARGETS ${${PROJECT_NAME}_LIBRARIES})
Expand Down Expand Up @@ -232,4 +238,4 @@ else()
)

endif()
unset(BUILD_ROS_SUPPORT CACHE)
unset(BUILD_ROS_SUPPORT CACHE)
66 changes: 66 additions & 0 deletions include/Planners/AStarSemantic.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#ifndef ASTARSemantic_HPP
#define ASTARSemantic_HPP
/**
* @file AStarSemantic.hpp
* @author Jose Antonio Cobano (jacobsua@upo.es)
*
* @brief This algorithm is a variation of the A*. The only
* difference is that it reimplements the computeG method adding the
* following cost term to the resturned result:
*
* auto cost_term = static_cast<unsigned int>(cost_weight_ * _suc * dist_scale_factor_reduced_);
*
* @version 0.1
* @date 2024-01-23
*
* @copyright Copyright (c) 2021
*
*/
#include <Planners/AStar.hpp>

namespace Planners{

/**
* @brief
*
*/
class AStarSemantic : public AStar
{

public:
/**
* @brief Construct a new AStarSemantic object
* @param _use_3d This parameter allows the user to choose between
* planning on a plane (8 directions possibles)
* or in the 3D full space (26 directions)
* @param _name Algorithm name stored internally
*
*/
AStarSemantic(bool _use_3d, std::string _name );

/**
* @brief Construct a new Cost Aware A Star M1 object
*
* @param _use_3d
*/
AStarSemantic(bool _use_3d);

protected:

/**
* @brief Overrided ComputeG function.
*
* @param _current Pointer to the current node
* @param _suc Pointer to the successor node
* @param _n_i The index of the direction in the directions vector.
* Depending on this index, the distance wi
* @param _dirs Number of directions used (to distinguish between 2D and 3D)
* @return unsigned int The G Value calculated by the function
*/
inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override;

};

}

#endif
66 changes: 66 additions & 0 deletions include/Planners/AStarSemanticCost.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#ifndef ASTARSemanticCost_HPP
#define ASTARSemanticCost_HPP
/**
* @file AStarSemantic.hpp
* @author Jose Antonio Cobano (jacobsua@upo.es)
*
* @brief This algorithm is a variation of the A*. The only
* difference is that it reimplements the computeG method adding the
* following cost term to the resturned result:
*
* auto cost_term = static_cast<unsigned int>(cost_weight_ * _suc * dist_scale_factor_reduced_);
*
* @version 0.1
* @date 2024-01-23
*
* @copyright Copyright (c) 2021
*
*/
#include <Planners/AStar.hpp>

namespace Planners{

/**
* @brief
*
*/
class AStarSemanticCost : public AStar
{

public:
/**
* @brief Construct a new AStarSemantic object
* @param _use_3d This parameter allows the user to choose between
* planning on a plane (8 directions possibles)
* or in the 3D full space (26 directions)
* @param _name Algorithm name stored internally
*
*/
AStarSemanticCost(bool _use_3d, std::string _name );

/**
* @brief Construct a new Cost Aware A Star M1 object
*
* @param _use_3d
*/
AStarSemanticCost(bool _use_3d);

protected:

/**
* @brief Overrided ComputeG function.
*
* @param _current Pointer to the current node
* @param _suc Pointer to the successor node
* @param _n_i The index of the direction in the directions vector.
* Depending on this index, the distance wi
* @param _dirs Number of directions used (to distinguish between 2D and 3D)
* @return unsigned int The G Value calculated by the function
*/
inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override;

};

}

#endif
89 changes: 89 additions & 0 deletions include/Planners/LazyThetaStarSemantic.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
#ifndef LAZYTHETASTARSEMANTIC_HPP
#define LAZYTHETASTARSEMANTIC_HPP
/**
* @file LazyThetaStarSemantic.hpp
* @author Jose Antonio Cobano (jacobsua@upo.es)
* @brief
* @version 0.1
* @date 2024-01-23
*
* @copyright Copyright (c) 2024
*
*/
#include <Planners/ThetaStarSemantic.hpp>

namespace Planners
{
/**
* @brief Lazy Theta* Algorithm Class
*
*/
class LazyThetaStarSemantic : public ThetaStarSemantic
{

public:

/**
* @brief Construct a new Semantic Lazy Theta Star object
*
* @param _use_3d This parameter allows the user to choose between planning on a plane
* (8 directions possibles) or in the 3D full space (26 directions)
* @param _name Algorithm name stored internally
*
*/
LazyThetaStarSemantic(bool _use_3d, std::string _name );

/**
* @brief Construct a new Semantic Lazy Theta Star object
*
* @param _use_3d
*/
LazyThetaStarSemantic(bool _use_3d);

/**
* @brief
*
* @param _source
* @param _target
* @return PathData
*/
virtual PathData findPath(const Vec3i &_source, const Vec3i &_target) override;

protected:

/**
* @brief Compute cost function of the Lazy version of the algorithm
*
* @param _s_aux Pointer to first node
* @param _s2_aux Pointer to second node
*/
inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override;

/**
* @brief SetVertex function
* Line of sight is checked inside this function
* @param _s_aux
*/
virtual void SetVertex(Node *_s_aux);

/**
* @brief
*
* @param _current
* @param _suc
* @param _n_i
* @param _dirs
* @return unsigned int
*/
inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override;

// Variable to ensure that the los is true between the parent of the current and one neighbour, so SetVertex function should not be executed
bool los_neighbour_{false}; /*!< TODO Comment */
int coef=3;


};

}

#endif
91 changes: 91 additions & 0 deletions include/Planners/LazyThetaStarSemanticCost.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
#ifndef LAZYTHETASTARSEMANTICCOST_HPP
#define LAZYTHETASTARSEMANTICCOST_HPP
/**
* @file LazyThetaStarSemantic.hpp
* @author Jose Antonio Cobano (jacobsua@upo.es)
* @brief
* @version 0.1
* @date 2024-01-23
*
* @copyright Copyright (c) 2024
*
*/
#include <Planners/ThetaStarSemanticCost.hpp>
// #include <Planners/ThetaStarSemantic.hpp>

namespace Planners
{
/**
* @brief Lazy Theta* Algorithm Class
*
*/
class LazyThetaStarSemanticCost : public ThetaStarSemanticCost
// class LazyThetaStarSemanticCost : public ThetaStarSemantic
{

public:

/**
* @brief Construct a new Semantic Lazy Theta Star object
*
* @param _use_3d This parameter allows the user to choose between planning on a plane
* (8 directions possibles) or in the 3D full space (26 directions)
* @param _name Algorithm name stored internally
*
*/
LazyThetaStarSemanticCost(bool _use_3d, std::string _name );

/**
* @brief Construct a new Semantic Lazy Theta Star object
*
* @param _use_3d
*/
LazyThetaStarSemanticCost(bool _use_3d);

/**
* @brief
*
* @param _source
* @param _target
* @return PathData
*/
virtual PathData findPath(const Vec3i &_source, const Vec3i &_target) override;

protected:

/**
* @brief Compute cost function of the Lazy version of the algorithm
*
* @param _s_aux Pointer to first node
* @param _s2_aux Pointer to second node
*/
inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override;

/**
* @brief SetVertex function
* Line of sight is checked inside this function
* @param _s_aux
*/
virtual void SetVertex(Node *_s_aux);

/**
* @brief
*
* @param _current
* @param _suc
* @param _n_i
* @param _dirs
* @return unsigned int
*/
inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override;

// Variable to ensure that the los is true between the parent of the current and one neighbour, so SetVertex function should not be executed
bool los_neighbour_{false}; /*!< TODO Comment */
int coef=3;


};

}

#endif
Loading

0 comments on commit 4dfadb0

Please sign in to comment.