Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Typedefs
Classes
Class List
Class Hierarchy
Class Members
All
Functions
Variables
Files
File List
File Members
All
Functions
src
easy_costmap.cpp
Go to the documentation of this file.
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2017, Locus Robotics
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the copyright holder nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*/
34
35
#include <
global_planner_tests/easy_costmap.h
>
36
#include <
global_planner_tests/util.h
>
37
#include <
map_server/image_loader.h
>
38
#include <string>
39
#include <vector>
40
#include <algorithm>
41
42
namespace
global_planner_tests
43
{
44
45
EasyCostmap::EasyCostmap
(
const
std::string& filename,
const
double
resolution,
const
bool
origin_at_center)
46
{
47
loadMapFromFile
(filename, resolution, origin_at_center);
48
}
49
50
void
EasyCostmap::loadMapFromFile
(
const
std::string& filename,
const
double
resolution,
const
bool
origin_at_center)
51
{
52
double
origin[3] = {0.0, 0.0, 0.0};
53
nav_msgs::GetMap::Response map_resp;
54
map_server::loadMapFromFile
(&map_resp,
resolve_filename
(filename).c_str(), resolution,
true
, 0.0, 0.0, origin,
RAW
);
55
56
if
(origin_at_center)
57
{
58
map_resp.map.info.origin.position.x = map_resp.map.info.width * resolution / -2;
59
map_resp.map.info.origin.position.y = map_resp.map.info.height * resolution / -2;
60
}
61
original_grid_
= map_resp.map;
62
original_grid_
.header.frame_id =
"map"
;
63
reset
();
64
}
65
66
void
EasyCostmap::reset
()
67
{
68
nav_grid::NavGridInfo
new_info;
69
new_info.
width
=
original_grid_
.info.width;
70
new_info.
height
=
original_grid_
.info.height;
71
new_info.
resolution
=
original_grid_
.info.resolution;
72
new_info.
frame_id
=
original_grid_
.header.frame_id;
73
new_info.
origin_x
=
original_grid_
.info.origin.position.x;
74
new_info.
origin_y
=
original_grid_
.info.origin.position.y;
75
76
if
(info_ != new_info)
77
{
78
info_ = new_info;
79
data_
.resize(info_.width * info_.height);
80
}
81
for
(
unsigned
int
i=0; i <
data_
.size(); i++)
82
{
83
data_
[i] =
static_cast<
unsigned
char
>
(
original_grid_
.data[i]);
84
}
85
}
86
87
}
// namespace global_planner_tests
nav_grid::NavGridInfo::height
unsigned int height
global_planner_tests::EasyCostmap::EasyCostmap
EasyCostmap()
Empty constructor. You need to call loadMapFromFile afterward.
Definition:
easy_costmap.h:62
nav_grid::NavGridInfo::origin_x
double origin_x
global_planner_tests::EasyCostmap::reset
void reset() override
Definition:
easy_costmap.cpp:66
easy_costmap.h
map_server::loadMapFromFile
void loadMapFromFile(nav_msgs::GetMap::Response *resp, const char *fname, double res, bool negate, double occ_th, double free_th, double *origin, MapMode mode=TRINARY)
global_planner_tests
Definition:
easy_costmap.h:42
image_loader.h
nav_grid::NavGridInfo::frame_id
std::string frame_id
nav_core2::BasicCostmap::data_
std::vector< unsigned char > data_
nav_grid::NavGridInfo
nav_grid::NavGridInfo::resolution
double resolution
RAW
RAW
nav_grid::NavGridInfo::width
unsigned int width
global_planner_tests::EasyCostmap::loadMapFromFile
void loadMapFromFile(const std::string &filename, const double resolution=0.1, const bool origin_at_center=false)
Definition:
easy_costmap.cpp:50
global_planner_tests::resolve_filename
std::string resolve_filename(const std::string &filename)
Replace a package:// prefix with the actual path to the given package.
Definition:
util.cpp:43
nav_grid::NavGridInfo::origin_y
double origin_y
util.h
global_planner_tests::EasyCostmap::original_grid_
nav_msgs::OccupancyGrid original_grid_
Definition:
easy_costmap.h:71
global_planner_tests
Author(s):
autogenerated on Sun Jul 3 2022 02:47:50