collision_checker.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef yocs_navi_toolkit_COLLISION_CHECKER_HPP_
9 #define yocs_navi_toolkit_COLLISION_CHECKER_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
17 #include <memory>
18 
19 /*****************************************************************************
20 ** Namespaces
21 *****************************************************************************/
22 
23 namespace yocs_navi_toolkit {
24 
25 /*****************************************************************************
26 ** Interfaces
27 *****************************************************************************/
28 
40 public:
55  bool inCollision(const float& x, const float& y, const float& yaw);
56 
57 private:
60  std::vector<geometry_msgs::Point> footprint_;
61  double inscribed_radius_, circumscribed_radius_; // properties of the footprint.
62 };
63 
64 typedef std::shared_ptr<CollisionChecker> CollisionCheckerPtr;
65 
66 /*****************************************************************************
67 ** Trailers
68 *****************************************************************************/
69 
70 } // namespace yocs_navi_toolkit
71 
72 #endif /* yocs_navi_toolkit_COLLISION_CHECKER_HPP_ */
std::shared_ptr< CollisionChecker > CollisionCheckerPtr
base_local_planner::CostmapModel costmap_model_
CollisionChecker(costmap_2d::Costmap2DROS *costmap_ros)
Initialise the checker with a costmap.
std::vector< geometry_msgs::Point > footprint_
Simple single-state collision checker.
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool inCollision(const float &x, const float &y, const float &yaw)
Check for collision along the boundaries of the footprint.
TFSIMD_FORCE_INLINE const tfScalar & x() const
costmap_2d::Costmap2DROS * costmap_ros_


yocs_navi_toolkit
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 15:53:55