forked from ANYbotics/grid_map
-
Notifications
You must be signed in to change notification settings - Fork 0
/
IteratorsDemo.cpp
258 lines (215 loc) · 6.88 KB
/
IteratorsDemo.cpp
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
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
/*
* IteratorsDemo.cpp
*
* Created on: Nov 4, 2014
* Author: Péter Fankhauser
* Institute: ETH Zurich, ANYbotics
*/
#include "grid_map_demos/IteratorsDemo.hpp"
// ROS
#include <geometry_msgs/PolygonStamped.h>
using namespace std;
using namespace ros;
using namespace grid_map;
namespace grid_map_demos {
IteratorsDemo::IteratorsDemo(ros::NodeHandle& nodeHandle)
: nodeHandle_(nodeHandle),
map_(vector<string>({"type"}))
{
ROS_INFO("Grid map iterators demo node started.");
gridMapPublisher_ = nodeHandle_.advertise<grid_map_msgs::GridMap>("grid_map", 1, true);
polygonPublisher_ = nodeHandle_.advertise<geometry_msgs::PolygonStamped>("polygon", 1, true);
// Setting up map.
map_.setGeometry(Length(1.0, 1.0), 0.05, Position(0.0, 0.0));
map_.setFrameId("map");
publish();
ros::Duration duration(2.0);
duration.sleep();
demoGridMapIterator();
demoSubmapIterator();
demoCircleIterator();
demoEllipseIterator();
demoSpiralIterator();
demoLineIterator();
demoPolygonIterator();
demoSlidingWindowIterator();
}
IteratorsDemo::~IteratorsDemo() {}
void IteratorsDemo::demoGridMapIterator()
{
ROS_INFO("Running grid map iterator demo.");
map_.clearAll();
publish();
// Note: In this example we locally store a reference to the map data
// for improved performance. See `iterator_benchmark.cpp` and the
// README.md for a comparison and more information.
grid_map::Matrix& data = map_["type"];
for (grid_map::GridMapIterator iterator(map_); !iterator.isPastEnd(); ++iterator) {
const int i = iterator.getLinearIndex();
data(i) = 1.0;
publish();
ros::Duration duration(0.01);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoSubmapIterator()
{
ROS_INFO("Running submap iterator demo.");
map_.clearAll();
publish();
Index submapStartIndex(3, 5);
Index submapBufferSize(12, 7);
for (grid_map::SubmapIterator iterator(map_, submapStartIndex, submapBufferSize);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
publish();
ros::Duration duration(0.02);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoCircleIterator()
{
ROS_INFO("Running circle iterator demo.");
map_.clearAll();
publish();
Position center(0.0, -0.15);
double radius = 0.4;
for (grid_map::CircleIterator iterator(map_, center, radius);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
publish();
ros::Duration duration(0.02);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoEllipseIterator()
{
ROS_INFO("Running ellipse iterator demo.");
map_.clearAll();
publish();
Position center(0.0, -0.15);
Length length(0.45, 0.9);
for (grid_map::EllipseIterator iterator(map_, center, length, M_PI_4);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
publish();
ros::Duration duration(0.02);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoSpiralIterator()
{
ROS_INFO("Running spiral iterator demo.");
map_.clearAll();
publish();
Position center(0.0, -0.15);
double radius = 0.4;
for (grid_map::SpiralIterator iterator(map_, center, radius);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
publish();
ros::Duration duration(0.02);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoLineIterator()
{
ROS_INFO("Running line iterator demo.");
map_.clearAll();
publish();
Index start(18, 2);
Index end(2, 13);
for (grid_map::LineIterator iterator(map_, start, end);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
publish();
ros::Duration duration(0.02);
duration.sleep();
}
ros::Duration duration(1.0);
duration.sleep();
}
void IteratorsDemo::demoPolygonIterator(const bool prepareForOtherDemos)
{
ROS_INFO("Running polygon iterator demo.");
map_.clearAll();
if (prepareForOtherDemos) map_["type"].setZero();
publish();
grid_map::Polygon polygon;
polygon.setFrameId(map_.getFrameId());
polygon.addVertex(Position( 0.480, 0.000));
polygon.addVertex(Position( 0.164, 0.155));
polygon.addVertex(Position( 0.116, 0.500));
polygon.addVertex(Position(-0.133, 0.250));
polygon.addVertex(Position(-0.480, 0.399));
polygon.addVertex(Position(-0.316, 0.000));
polygon.addVertex(Position(-0.480, -0.399));
polygon.addVertex(Position(-0.133, -0.250));
polygon.addVertex(Position( 0.116, -0.500));
polygon.addVertex(Position( 0.164, -0.155));
polygon.addVertex(Position( 0.480, 0.000));
geometry_msgs::PolygonStamped message;
grid_map::PolygonRosConverter::toMessage(polygon, message);
polygonPublisher_.publish(message);
for (grid_map::PolygonIterator iterator(map_, polygon);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = 1.0;
if (!prepareForOtherDemos) {
publish();
ros::Duration duration(0.02);
duration.sleep();
}
}
if (!prepareForOtherDemos) {
ros::Duration duration(1.0);
duration.sleep();
}
}
void IteratorsDemo::demoSlidingWindowIterator()
{
ROS_INFO("Running sliding window iterator demo.");
demoPolygonIterator(true);
publish();
const size_t windowSize = 3;
const grid_map::SlidingWindowIterator::EdgeHandling edgeHandling = grid_map::SlidingWindowIterator::EdgeHandling::CROP;
map_.add("copy", map_["type"]);
for (grid_map::SlidingWindowIterator iterator(map_, "copy", edgeHandling, windowSize);
!iterator.isPastEnd(); ++iterator) {
map_.at("type", *iterator) = iterator.getData().meanOfFinites(); // Blurring.
publish();
// Visualize sliding window as polygon.
grid_map::Polygon polygon;
Position center;
map_.getPosition(*iterator, center);
const Length windowHalfLength(Length::Constant(0.5 * (double) windowSize * map_.getResolution()));
polygon.addVertex(center + (Eigen::Array2d(-1.0,-1.0) * windowHalfLength).matrix());
polygon.addVertex(center + (Eigen::Array2d(-1.0, 1.0) * windowHalfLength).matrix());
polygon.addVertex(center + (Eigen::Array2d( 1.0, 1.0) * windowHalfLength).matrix());
polygon.addVertex(center + (Eigen::Array2d( 1.0,-1.0) * windowHalfLength).matrix());
polygon.setFrameId(map_.getFrameId());
geometry_msgs::PolygonStamped message;
grid_map::PolygonRosConverter::toMessage(polygon, message);
polygonPublisher_.publish(message);
ros::Duration duration(0.02);
duration.sleep();
}
}
void IteratorsDemo::publish()
{
map_.setTimestamp(ros::Time::now().toNSec());
grid_map_msgs::GridMap message;
grid_map::GridMapRosConverter::toMessage(map_, message);
gridMapPublisher_.publish(message);
ROS_DEBUG("Grid map (timestamp %f) published.", message.info.header.stamp.toSec());
}
} /* namespace */