src
gpp_update_map.cpp
Go to the documentation of this file.
1
/*
2
* MIT License
3
*
4
* Copyright (c) 2021 Dima Dorezyuk
5
*
6
* Permission is hereby granted, free of charge, to any person obtaining a copy
7
* of this software and associated documentation files (the "Software"), to deal
8
* in the Software without restriction, including without limitation the rights
9
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10
* copies of the Software, and to permit persons to whom the Software is
11
* furnished to do so, subject to the following conditions:
12
*
13
* The above copyright notice and this permission notice shall be included in
14
* all copies or substantial portions of the Software.
15
*
16
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22
* SOFTWARE.
23
*/
24
25
#include <
gpp_update_map/gpp_update_map.hpp
>
26
27
#include <
pluginlib/class_list_macros.h
>
28
#include <
ros/ros.h
>
29
30
namespace
gpp_update_map
{
31
33
constexpr
char
__name
[] =
"[gpp_update_map]: "
;
34
35
// custom prints with the plugin name
36
#define GPP_DEBUG(args) ROS_DEBUG_STREAM(__name << args)
37
#define GPP_WARN(args) ROS_WARN_STREAM(__name << args)
38
39
bool
40
GppUpdateMap::preProcess
(
Pose
& _start,
Pose
& _goal) {
41
// just to be sure
42
if
(!
map_
) {
43
GPP_WARN
(
"map_ cannot be nullptr: call first initialize"
);
44
return
false
;
45
}
46
47
// uppdate the map
48
map_
->
updateMap
();
49
return
true
;
50
}
51
52
void
53
GppUpdateMap::initialize
(
const
std::string& _name,
Map
* _map) {
54
// we might check here for nullptr, but it maybe the case that the user sets
55
// this on purpose...
56
map_
= _map;
57
}
58
59
}
// namespace gpp_update_map
60
61
// register the plugin
62
PLUGINLIB_EXPORT_CLASS
(
gpp_update_map::GppUpdateMap
,
63
gpp_interface::PrePlanningInterface
);
gpp_update_map::GppUpdateMap
Class will call updateMap on the passed map.
Definition:
gpp_update_map.hpp:43
ros.h
gpp_interface::PrePlanningInterface::Pose
geometry_msgs::PoseStamped Pose
gpp_update_map.hpp
GPP_WARN
#define GPP_WARN(args)
Definition:
gpp_update_map.cpp:37
class_list_macros.h
gpp_update_map::GppUpdateMap::map_
Map * map_
Definition:
gpp_update_map.hpp:51
gpp_update_map::GppUpdateMap::preProcess
bool preProcess(Pose &_start, Pose &_goal) override
Definition:
gpp_update_map.cpp:40
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(gpp_update_map::GppUpdateMap, gpp_interface::PrePlanningInterface)
gpp_interface::PrePlanningInterface
gpp_update_map::GppUpdateMap::initialize
void initialize(const std::string &_name, Map *_map) override
Definition:
gpp_update_map.cpp:53
gpp_update_map::__name
constexpr char __name[]
plugin name
Definition:
gpp_update_map.cpp:33
gpp_update_map
Definition:
gpp_update_map.hpp:29
costmap_2d::Costmap2DROS::updateMap
void updateMap()
costmap_2d::Costmap2DROS
gpp_update_map
Author(s):
autogenerated on Wed Mar 2 2022 00:21:29