costmap_model.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef TRAJECTORY_ROLLOUT_COSTMAP_MODEL_
38 #define TRAJECTORY_ROLLOUT_COSTMAP_MODEL_
39 
41 // For obstacle data access
42 #include <costmap_2d/costmap_2d.h>
43 
44 namespace base_local_planner {
50  class CostmapModel : public WorldModel {
51  public:
57  CostmapModel(const costmap_2d::Costmap2D& costmap);
58 
62  virtual ~CostmapModel(){}
64 
76  virtual double footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
77  double inscribed_radius, double circumscribed_radius);
78 
87  double lineCost(int x0, int x1, int y0, int y1) const;
88 
95  double pointCost(int x, int y) const;
96 
97  private:
99 
100  };
101 };
102 #endif
base_local_planner::WorldModel::footprintCost
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...
base_local_planner::CostmapModel::footprintCost
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...
Definition: costmap_model.cpp:47
costmap_2d.h
costmap_2d::Costmap2D
base_local_planner::CostmapModel::costmap_
const costmap_2d::Costmap2D & costmap_
Allows access of costmap obstacle information.
Definition: costmap_model.h:133
base_local_planner::CostmapModel
A class that implements the WorldModel interface to provide grid based collision checks for the traje...
Definition: costmap_model.h:85
base_local_planner::CostmapModel::pointCost
double pointCost(int x, int y) const
Checks the cost of a point in the costmap.
Definition: costmap_model.cpp:134
base_local_planner::CostmapModel::lineCost
double lineCost(int x0, int x1, int y0, int y1) const
Rasterizes a line in the costmap grid and checks for collisions.
Definition: costmap_model.cpp:116
base_local_planner::WorldModel
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
Definition: world_model.h:87
base_local_planner::CostmapModel::~CostmapModel
virtual ~CostmapModel()
Destructor for the world model.
Definition: costmap_model.h:97
base_local_planner
Definition: costmap_model.h:44
base_local_planner::CostmapModel::CostmapModel
CostmapModel(const costmap_2d::Costmap2D &costmap)
Constructor for the CostmapModel.
Definition: costmap_model.cpp:45
world_model.h


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:23