Newer
Older
Niklas Yann Wettengel
committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
#include "MaskingManager.h"
#include "ros/ros.h"
#include <homer_mapnav_msgs/ModifyMap.h>
#include <sstream>
using namespace std;
MaskingManager::MaskingManager(int mapSize, float resolution)
{
m_CellSize = resolution;
m_Width = mapSize / m_CellSize + 1;
m_Height = mapSize / m_CellSize + 1;
ROS_INFO_STREAM( "Creating " << m_Width << " x " << m_Height << " map." );
m_MaskingMap.info.resolution = m_CellSize;
m_MaskingMap.info.height = m_Height;
m_MaskingMap.info.width = m_Width;
m_MaskingMap.data.resize(m_Width * m_Height);
std::fill( m_MaskingMap.data.begin(), m_MaskingMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED );
m_SlamMap.info.resolution = m_CellSize;
m_SlamMap.info.height = m_Height;
m_SlamMap.info.width = m_Width;
m_SlamMap.data.resize(m_Width * m_Height);
std::fill( m_SlamMap.data.begin(), m_SlamMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED );
}
MaskingManager::~MaskingManager()
{}
nav_msgs::OccupancyGrid::ConstPtr MaskingManager::modifyMap(homer_mapnav_msgs::ModifyMap::ConstPtr msg)
{
//reset SLAM mask map before each masking
std::fill( m_SlamMap.data.begin(), m_SlamMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED );
drawPolygon(msg->region, msg->maskAction, msg->mapLayer);
nav_msgs::OccupancyGrid::ConstPtr ret;
if(msg->mapLayer == 0)
{
ret = boost::make_shared<const::nav_msgs::OccupancyGrid>(m_SlamMap);
}
else
{
ret = boost::make_shared<const::nav_msgs::OccupancyGrid>(m_MaskingMap);
}
return ret;
}
nav_msgs::OccupancyGrid::ConstPtr MaskingManager::resetMap()
{
std::fill( m_MaskingMap.data.begin(), m_MaskingMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED );
nav_msgs::OccupancyGrid::ConstPtr ret = boost::make_shared<const::nav_msgs::OccupancyGrid>(m_MaskingMap);
return ret;
}
void MaskingManager::replaceMap(nav_msgs::OccupancyGrid map)
{
if(map.data.size() != 0)
m_MaskingMap = map;
else
std::fill( m_MaskingMap.data.begin(), m_MaskingMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED );
}
void MaskingManager::drawPolygon ( vector< geometry_msgs::Point > vertices , int value , int mapLayer)
{
if ( vertices.size() == 0 )
{
ROS_INFO_STREAM( "No vertices given!" );
return;
}
//make temp. map
std::vector<int> data(m_Width * m_Height);
for ( int i = 0; i < data.size(); i++ )
{
data[i] = 0;
}
//draw the lines surrounding the polygon
for ( unsigned int i = 0; i < vertices.size(); i++ )
{
int i2 = ( i+1 ) % vertices.size();
drawLine ( data, vertices[i].x, vertices[i].y, vertices[i2].x, vertices[i2].y, 1);
}
//calculate a point in the middle of the polygon
float midX = 0;
float midY = 0;
for ( unsigned int i = 0; i < vertices.size(); i++ )
{
midX += vertices[i].x;
midY += vertices[i].y;
}
midX /= vertices.size();
midY /= vertices.size();
//fill polygon
fillPolygon ( data, (int)midX, (int)midY, 1 );
//copy polygon to masking map or slam map (according to parameter mapLayer)
for ( int i = 0; i < data.size(); i++ )
{
if ( data[i] != 0 )
{
switch(mapLayer)
{
case 0: //SLAM map
m_SlamMap.data[i] = value;
break;
case 1: //Kinect Map. apply masking to masking map
case 2: //masking map
m_MaskingMap.data[i] = value;
break;
}
}
}
}
void MaskingManager::drawLine ( std::vector<int> &data, int startX, int startY, int endX, int endY, int value )
{
//bresenham algorithm
int x, y, t, dist, xerr, yerr, dx, dy, incx, incy;
// compute distances
dx = endX - startX;
dy = endY - startY;
// compute increment
if ( dx < 0 )
{
incx = -1;
dx = -dx;
}
else
{
incx = dx ? 1 : 0;
}
if ( dy < 0 )
{
incy = -1;
dy = -dy;
}
else
{
incy = dy ? 1 : 0;
}
// which distance is greater?
dist = ( dx > dy ) ? dx : dy;
// initializing
x = startX;
y = startY;
xerr = dx;
yerr = dy;
// compute cells
for ( t = 0; t < dist; t++ )
{
data[x + m_Width * y] = value;
xerr += dx;
yerr += dy;
if ( xerr > dist )
{
xerr -= dist;
x += incx;
}
if ( yerr > dist )
{
yerr -= dist;
y += incy;
}
}
}
void MaskingManager::fillPolygon ( std::vector<int> &data, int x, int y, int value )
{
int index = x + m_Width * y;
if ( value != data[index] )
{
data[index] = value;
fillPolygon ( data, x + 1, y, value );
fillPolygon ( data, x - 1, y, value );
fillPolygon ( data, x, y + 1, value );
fillPolygon ( data, x, y - 1, value );
}
}