include
costmap_cspace
costmap_3d_layer
stop_propagation.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_STOP_PROPAGATION_H
31
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_STOP_PROPAGATION_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
Costmap3dLayerStopPropagation
:
public
Costmap3dLayerBase
45
{
46
public
:
47
using
Ptr
= std::shared_ptr<Costmap3dLayerStopPropagation>;
48
49
public
:
50
void
loadConfig
(
XmlRpc::XmlRpcValue
config)
51
{
52
}
53
void
setMapMetaData
(
const
costmap_cspace_msgs::MapMetaData3D& info)
54
{
55
}
56
57
protected
:
58
int
getRangeMax
()
const
59
{
60
return
0;
61
}
62
bool
updateChain
(
const
bool
output)
63
{
64
region_
=
UpdatedRegion
(
65
0, 0, 0,
map_
->info.width,
map_
->info.height,
map_
->info.angle,
ros::Time
(0));
66
for
(
auto
& c :
map_overlay_
->data)
67
c = -1;
68
return
false
;
69
}
70
void
updateCSpace
(
71
const
nav_msgs::OccupancyGrid::ConstPtr& map,
72
const
UpdatedRegion
& region)
73
{
74
}
75
};
76
}
// namespace costmap_cspace
77
78
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_STOP_PROPAGATION_H
costmap_cspace::Costmap3dLayerBase::map_overlay_
CSpace3DMsg::Ptr map_overlay_
Definition:
base.h:263
costmap_cspace::Costmap3dLayerStopPropagation::updateCSpace
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion)
Definition:
stop_propagation.h:70
costmap_cspace::UpdatedRegion
Definition:
base.h:102
base.h
costmap_cspace::Costmap3dLayerBase
Definition:
base.h:252
costmap_cspace::Costmap3dLayerStopPropagation::getRangeMax
int getRangeMax() const
Definition:
stop_propagation.h:58
costmap_cspace::Costmap3dLayerBase::region_
UpdatedRegion region_
Definition:
base.h:266
costmap_cspace
Definition:
costmap_3d.h:46
ros::Time
costmap_cspace::Costmap3dLayerStopPropagation::updateChain
bool updateChain(const bool output)
Definition:
stop_propagation.h:62
costmap_cspace::Costmap3dLayerStopPropagation::loadConfig
void loadConfig(XmlRpc::XmlRpcValue config)
Definition:
stop_propagation.h:50
costmap_cspace::Costmap3dLayerStopPropagation
Definition:
stop_propagation.h:44
costmap_cspace::Costmap3dLayerStopPropagation::setMapMetaData
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
Definition:
stop_propagation.h:53
costmap_cspace::Costmap3dLayerBase::map_
CSpace3DMsg::Ptr map_
Definition:
base.h:262
XmlRpc::XmlRpcValue
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