37 #ifndef TRAJECTORY_ROLLOUT_COSTMAP_MODEL_ 38 #define TRAJECTORY_ROLLOUT_COSTMAP_MODEL_ 76 virtual double footprintCost(
const geometry_msgs::Point& position,
const std::vector<geometry_msgs::Point>& footprint,
77 double inscribed_radius,
double circumscribed_radius);
87 double lineCost(
int x0,
int x1,
int y0,
int y1)
const;
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
const costmap_2d::Costmap2D & costmap_
Allows access of costmap obstacle information.
virtual ~CostmapModel()
Destructor for the world model.
TFSIMD_FORCE_INLINE const tfScalar & y() const
double pointCost(int x, int y) const
Checks the cost of a point in the costmap.
TFSIMD_FORCE_INLINE const tfScalar & x() const
double lineCost(int x0, int x1, int y0, int y1) const
Rasterizes a line in the costmap grid and checks for collisions.
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid...
A class that implements the WorldModel interface to provide grid based collision checks for the traje...
CostmapModel(const costmap_2d::Costmap2D &costmap)
Constructor for the CostmapModel.