Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
nav2_costmap_2d
include
nav2_costmap_2d
footprint_collision_checker.hpp
1
// Copyright (c) 2019 Intel Corporation
2
//
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
// you may not use this file except in compliance with the License.
5
// You may obtain a copy of the License at
6
//
7
// http://www.apache.org/licenses/LICENSE-2.0
8
//
9
// Unless required by applicable law or agreed to in writing, software
10
// distributed under the License is distributed on an "AS IS" BASIS,
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
// See the License for the specific language governing permissions and
13
// limitations under the License.
14
//
15
// Modified by: Shivang Patel (shivaang14@gmail.com)
16
17
#ifndef NAV2_COSTMAP_2D__FOOTPRINT_COLLISION_CHECKER_HPP_
18
#define NAV2_COSTMAP_2D__FOOTPRINT_COLLISION_CHECKER_HPP_
19
20
#include <string>
21
#include <vector>
22
#include <memory>
23
#include <algorithm>
24
25
#include "rclcpp/rclcpp.hpp"
26
#include "geometry_msgs/msg/pose_stamped.hpp"
27
#include "geometry_msgs/msg/pose2_d.hpp"
28
#include "nav2_costmap_2d/costmap_2d.hpp"
29
#include "nav2_util/robot_utils.hpp"
30
31
namespace
nav2_costmap_2d
32
{
33
typedef
std::vector<geometry_msgs::msg::Point> Footprint;
34
39
template
<
typename
CostmapT>
40
class
FootprintCollisionChecker
41
{
42
public
:
46
FootprintCollisionChecker
();
50
explicit
FootprintCollisionChecker
(CostmapT costmap);
54
double
footprintCost
(
const
Footprint & footprint);
58
double
footprintCostAtPose
(
double
x,
double
y,
double
theta,
const
Footprint & footprint);
62
double
lineCost
(
int
x0,
int
x1,
int
y0,
int
y1)
const
;
66
bool
worldToMap
(
double
wx,
double
wy,
unsigned
int
& mx,
unsigned
int
& my);
70
double
pointCost
(
int
x,
int
y)
const
;
74
void
setCostmap
(CostmapT costmap);
78
CostmapT
getCostmap
()
79
{
80
return
costmap_;
81
}
82
83
protected
:
84
CostmapT costmap_;
85
};
86
87
}
// namespace nav2_costmap_2d
88
89
#endif
// NAV2_COSTMAP_2D__FOOTPRINT_COLLISION_CHECKER_HPP_
nav2_costmap_2d::FootprintCollisionChecker
Checker for collision with a footprint on a costmap.
Definition:
footprint_collision_checker.hpp:41
nav2_costmap_2d::FootprintCollisionChecker::FootprintCollisionChecker
FootprintCollisionChecker()
A constructor.
Definition:
footprint_collision_checker.cpp:35
nav2_costmap_2d::FootprintCollisionChecker::lineCost
double lineCost(int x0, int x1, int y0, int y1) const
Get the cost for a line segment.
Definition:
footprint_collision_checker.cpp:88
nav2_costmap_2d::FootprintCollisionChecker::getCostmap
CostmapT getCostmap()
Get the current costmap object.
Definition:
footprint_collision_checker.hpp:78
nav2_costmap_2d::FootprintCollisionChecker::worldToMap
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)
Get the map coordinates from a world point.
Definition:
footprint_collision_checker.cpp:110
nav2_costmap_2d::FootprintCollisionChecker::footprintCostAtPose
double footprintCostAtPose(double x, double y, double theta, const Footprint &footprint)
Find the footprint cost a a post with an unoriented footprint.
Definition:
footprint_collision_checker.cpp:129
nav2_costmap_2d::FootprintCollisionChecker::footprintCost
double footprintCost(const Footprint &footprint)
Find the footprint cost in oriented footprint.
Definition:
footprint_collision_checker.cpp:48
nav2_costmap_2d::FootprintCollisionChecker::setCostmap
void setCostmap(CostmapT costmap)
Set the current costmap object to use for collision detection.
Definition:
footprint_collision_checker.cpp:123
nav2_costmap_2d::FootprintCollisionChecker::pointCost
double pointCost(int x, int y) const
Get the cost of a point.
Definition:
footprint_collision_checker.cpp:117
nav2_costmap_2d
Definition:
clear_costmap_service.hpp:31
Generated by
1.9.1