include
costmap_cspace
costmap_3d_layer
unknown_handle.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2014-2018, the neonavigation authors
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the copyright holder nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
30
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
31
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
32
33
#include <memory>
34
35
#include <geometry_msgs/PolygonStamped.h>
36
#include <nav_msgs/OccupancyGrid.h>
37
#include <costmap_cspace_msgs/CSpace3D.h>
38
#include <costmap_cspace_msgs/CSpace3DUpdate.h>
39
40
#include <
costmap_cspace/costmap_3d_layer/base.h
>
41
42
namespace
costmap_cspace
43
{
44
class
Costmap3dLayerUnknownHandle
:
public
Costmap3dLayerBase
45
{
46
public
:
47
using
Ptr
= std::shared_ptr<Costmap3dLayerUnknownHandle>;
48
49
protected
:
50
int8_t
unknown_cost_
;
51
52
public
:
53
Costmap3dLayerUnknownHandle
()
54
:
unknown_cost_
(-1)
55
{
56
}
57
void
loadConfig
(
XmlRpc::XmlRpcValue
config)
58
{
59
if
(config.
hasMember
(
"unknown_cost"
))
60
{
61
unknown_cost_
=
static_cast<
int
>
(config[
"unknown_cost"
]);
62
}
63
}
64
void
setMapMetaData
(
const
costmap_cspace_msgs::MapMetaData3D& info)
65
{
66
}
67
68
protected
:
69
int
getRangeMax
()
const
70
{
71
return
0;
72
}
73
bool
updateChain
(
const
bool
output)
74
{
75
for
(
76
size_t
a =
region_
.
yaw_
;
77
static_cast<
int
>
(a) <
region_
.
yaw_
+
region_
.
angle_
&& a < map_->info.angle;
78
++a)
79
{
80
for
(
81
size_t
y =
region_
.
y_
;
82
static_cast<
int
>
(y) <
region_
.
y_
+
region_
.
height_
&& y < map_->info.height;
83
++y)
84
{
85
for
(
86
size_t
x =
region_
.
x_
;
87
static_cast<
int
>
(x) <
region_
.
x_
+
region_
.
width_
&& x < map_->info.width;
88
++x)
89
{
90
auto
& m =
map_overlay_
->getCost(x, y, a);
91
if
(m < 0)
92
m =
unknown_cost_
;
93
}
94
}
95
}
96
return
false
;
97
}
98
void
updateCSpace
(
99
const
nav_msgs::OccupancyGrid::ConstPtr& map,
100
const
UpdatedRegion
& region)
101
{
102
}
103
};
104
}
// namespace costmap_cspace
105
106
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
costmap_cspace::Costmap3dLayerBase::map_overlay_
CSpace3DMsg::Ptr map_overlay_
Definition:
base.h:263
costmap_cspace::Costmap3dLayerUnknownHandle::setMapMetaData
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition:
unknown_handle.h:64
costmap_cspace::Costmap3dLayerUnknownHandle::Costmap3dLayerUnknownHandle
Costmap3dLayerUnknownHandle()
Definition:
unknown_handle.h:53
costmap_cspace::UpdatedRegion::height_
int height_
Definition:
base.h:106
costmap_cspace::UpdatedRegion::angle_
int angle_
Definition:
base.h:106
costmap_cspace::UpdatedRegion
Definition:
base.h:102
costmap_cspace::UpdatedRegion::y_
int y_
Definition:
base.h:105
costmap_cspace::UpdatedRegion::width_
int width_
Definition:
base.h:106
base.h
costmap_cspace::Costmap3dLayerUnknownHandle::updateCSpace
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion)
Definition:
unknown_handle.h:98
costmap_cspace::Costmap3dLayerBase
Definition:
base.h:252
costmap_cspace::Costmap3dLayerUnknownHandle::updateChain
bool updateChain(const bool output)
Definition:
unknown_handle.h:73
costmap_cspace::Costmap3dLayerBase::region_
UpdatedRegion region_
Definition:
base.h:266
costmap_cspace::Costmap3dLayerUnknownHandle
Definition:
unknown_handle.h:44
costmap_cspace
Definition:
costmap_3d.h:46
costmap_cspace::Costmap3dLayerUnknownHandle::getRangeMax
int getRangeMax() const
Definition:
unknown_handle.h:69
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
costmap_cspace::UpdatedRegion::x_
int x_
Definition:
base.h:105
costmap_cspace::UpdatedRegion::yaw_
int yaw_
Definition:
base.h:105
XmlRpc::XmlRpcValue
costmap_cspace::Costmap3dLayerUnknownHandle::unknown_cost_
int8_t unknown_cost_
Definition:
unknown_handle.h:50
costmap_cspace::Costmap3dLayerUnknownHandle::loadConfig
void loadConfig(XmlRpc::XmlRpcValue config)
Definition:
unknown_handle.h:57
costmap_cspace::Costmap3dLayerBase::Ptr
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition:
base.h:255
costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10