@@ -40,64 +40,167 @@ void SpiralSTC::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_r
40
40
std::list<gridNode_t> SpiralSTC::spiral (std::vector<std::vector<bool > > const & grid, std::list<gridNode_t>& init,
41
41
std::vector<std::vector<bool > >& visited)
42
42
{
43
- int dx, dy, dx_prev, x2, y2, i, nRows = grid.size (), nCols = grid[0 ].size ();
44
- // Spiral filling of the open space
43
+ int dx, dy, x2, y2, i, nRows = grid.size (), nCols = grid[0 ].size ();
44
+ // Mountain pattern filling of the open space
45
45
// Copy incoming list to 'end'
46
- std::list<gridNode_t> pathNodes (init);
47
- // Create iterator for gridNode_t list and let it point to the last element of end
48
- std::list<gridNode_t>::iterator it = --(pathNodes.end ());
49
- if (pathNodes.size () > 1 ) // if list is length 1, keep iterator at end
50
- it--; // Let iterator point to second to last element
46
+ std::list<gridNode_t> pathNodes (init);
47
+
48
+ // set initial direction towards longest side
49
+ int robot_dir = point;
50
+ int pattern_dir = point;
51
+ if (nRows >= nCols) {
52
+ if (pathNodes.back ().pos .y < nRows / 2 ) {
53
+ robot_dir = north;
54
+ dy = 1 ;
55
+ }
56
+ else {
57
+ robot_dir = south;
58
+ dy = -1 ;
59
+ }
60
+ } else {
61
+ if (pathNodes.back ().pos .x < nCols / 2 ) {
62
+ robot_dir = east;
63
+ dx = 1 ;
64
+ }
65
+ else {
66
+ robot_dir = west;
67
+ dx = -1 ;
68
+ }
69
+ }
51
70
52
- gridNode_t prev = *(it);
53
71
bool done = false ;
54
72
while (!done)
55
73
{
56
- if (it != pathNodes.begin ())
57
- {
58
- // turn ccw
59
- dx = pathNodes.back ().pos .x - prev.pos .x ;
60
- dy = pathNodes.back ().pos .y - prev.pos .y ;
61
- dx_prev = dx;
62
- dx = -dy;
63
- dy = dx_prev;
64
- }
65
- else
66
- {
67
- // Initialize spiral direction towards y-axis
68
- dx = 0 ;
69
- dy = 1 ;
70
- }
71
- done = true ;
72
-
73
- for (int i = 0 ; i < 4 ; ++i)
74
- {
74
+ // 1. drive straight until hit wall
75
+ bool hitWall = false ;
76
+ while (!hitWall) {
75
77
x2 = pathNodes.back ().pos .x + dx;
76
78
y2 = pathNodes.back ().pos .y + dy;
77
- if (x2 >= 0 && x2 < nCols && y2 >= 0 && y2 < nRows)
79
+ if (! validMove (x2, y2, nCols, nRows, grid, visited))
78
80
{
79
- if (grid[y2][x2] == eNodeOpen && visited[y2][x2] == eNodeOpen)
80
- {
81
+ hitWall = true ;
82
+ x2 = pathNodes.back ().pos .x ;
83
+ y2 = pathNodes.back ().pos .y ;
84
+ break ;
85
+ }
86
+ if (!hitWall) {
81
87
Point_t new_point = { x2, y2 };
82
88
gridNode_t new_node =
83
89
{
84
90
new_point, // Point: x,y
85
91
0 , // Cost
86
92
0 , // Heuristic
87
93
};
88
- prev = pathNodes.back ();
89
94
pathNodes.push_back (new_node);
90
- it = --(pathNodes.end ());
91
95
visited[y2][x2] = eNodeVisited; // Close node
92
- done = false ;
93
- break ;
96
+ }
97
+ }
98
+
99
+ // 2. check left and right after hitting wall, then change direction
100
+ if (robot_dir == north || robot_dir == south)
101
+ {
102
+ if (!validMove (x2 + 1 , y2, nCols, nRows, grid, visited)
103
+ && !validMove (x2 - 1 , y2, nCols, nRows, grid, visited)) {
104
+ // dead end, exit
105
+ done = true ;
106
+ break ;
107
+ } else if (!validMove (x2 + 1 , y2, nCols, nRows, grid, visited)) {
108
+ // east is occupied, travel towards west
109
+ x2--;
110
+ pattern_dir = west;
111
+ } else if (!validMove (x2 - 1 , y2, nCols, nRows, grid, visited)) {
112
+ // west is occupied, travel towards east
113
+ x2++;
114
+ pattern_dir = east;
115
+ } else {
116
+ // both sides are opened. If don't have a prefered turn direction, travel towards farthest edge
117
+ if (!(pattern_dir == east || pattern_dir == west)) {
118
+ if (x2 < nCols / 2 ) { // east
119
+ pattern_dir = east;
120
+ } else { // west
121
+ pattern_dir = west;
122
+ }
123
+ }
124
+ if (pattern_dir = east) {
125
+ x2++;
126
+ } else if (pattern_dir = west) {
127
+ x2--;
94
128
}
95
129
}
96
- // try next direction cw
97
- dx_prev = dx;
98
- dx = dy;
99
- dy = -dx_prev;
130
+
131
+ // add Nodes to List
132
+ Point_t new_point = { x2, y2 };
133
+ gridNode_t new_node =
134
+ {
135
+ new_point, // Point: x,y
136
+ 0 , // Cost
137
+ 0 , // Heuristic
138
+ };
139
+ pathNodes.push_back (new_node);
140
+ visited[y2][x2] = eNodeVisited; // Close node
141
+
142
+ // change direction 180 deg
143
+ if (robot_dir == north) {
144
+ robot_dir = south;
145
+ dy = -1 ;
146
+ } else if (robot_dir == south) {
147
+ robot_dir = north;
148
+ dy = 1 ;
149
+ }
100
150
}
151
+ else if (robot_dir == east || robot_dir == west)
152
+ {
153
+ if (!validMove (x2, y2 + 1 , nCols, nRows, grid, visited)
154
+ && !validMove (x2, y2 - 1 , nCols, nRows, grid, visited)) {
155
+ // dead end, exit
156
+ done = true ;
157
+ break ;
158
+ } else if (!validMove (x2, y2 + 1 , nCols, nRows, grid, visited)) {
159
+ // north is occupied, travel towards south
160
+ y2--;
161
+ pattern_dir = south;
162
+ } else if (!validMove (x2, y2 - 1 , nCols, nRows, grid, visited)) {
163
+ // south is occupied, travel towards north
164
+ y2++;
165
+ pattern_dir = north;
166
+ } else {
167
+ // both sides are opened. If don't have a prefered turn direction, travel towards farthest edge
168
+ if (!(pattern_dir == north || pattern_dir == south)) {
169
+ if (y2 < nRows / 2 ) { // north
170
+ pattern_dir = north;
171
+ } else { // south
172
+ pattern_dir = south;
173
+ }
174
+ }
175
+ if (pattern_dir = north) {
176
+ y2++;
177
+ } else if (pattern_dir = south) {
178
+ y2--;
179
+ }
180
+ }
181
+
182
+ // add Nodes to List
183
+ Point_t new_point = { x2, y2 };
184
+ gridNode_t new_node =
185
+ {
186
+ new_point, // Point: x,y
187
+ 0 , // Cost
188
+ 0 , // Heuristic
189
+ };
190
+ pathNodes.push_back (new_node);
191
+ visited[y2][x2] = eNodeVisited; // Close node
192
+
193
+ // change direction 180 deg
194
+ if (robot_dir == east) {
195
+ robot_dir = west;
196
+ dx = -1 ;
197
+ } else if (robot_dir == west) {
198
+ robot_dir = east;
199
+ dx = 1 ;
200
+ }
201
+ }
202
+ // Log
203
+ printPathNodes (pathNodes);
101
204
}
102
205
return pathNodes;
103
206
}
@@ -117,6 +220,7 @@ std::list<Point_t> SpiralSTC::spiral_stc(std::vector<std::vector<bool> > const&
117
220
x = init.x ;
118
221
y = init.y ;
119
222
223
+ // add initial point to pathNodes
120
224
Point_t new_point = { x, y };
121
225
gridNode_t new_node =
122
226
{
@@ -129,31 +233,34 @@ std::list<Point_t> SpiralSTC::spiral_stc(std::vector<std::vector<bool> > const&
129
233
pathNodes.push_back (new_node);
130
234
visited[y][x] = eNodeVisited;
131
235
236
+ std::list<Point_t> goals = map_2_goals (visited, eNodeOpen); // Retrieve all goalpoints (Cells not visited)
237
+ std::list<gridNode_t>::iterator it;
238
+
132
239
#ifdef DEBUG_PLOT
133
240
ROS_INFO (" Grid before walking is: " );
134
241
printGrid (grid, visited, fullPath);
135
242
#endif
136
243
137
- pathNodes = SpiralSTC::spiral (grid, pathNodes, visited); // First spiral fill
138
- std::list<Point_t> goals = map_2_goals (visited, eNodeOpen); // Retrieve remaining goalpoints
139
- // Add points to full path
140
- std::list<gridNode_t>::iterator it;
141
- for (it = pathNodes.begin (); it != pathNodes.end (); ++it)
244
+ while (goals.size () != 0 )
142
245
{
143
- Point_t newPoint = { it->pos .x , it->pos .y };
144
- visited_counter++;
145
- fullPath.push_back (newPoint);
146
- }
147
- // Remove all elements from pathNodes list except last element
148
- pathNodes.erase (pathNodes.begin (), --(pathNodes.end ()));
246
+ // Spiral fill from current position
247
+ // TODO: Convert to U-turn pattern
248
+ pathNodes = spiral (grid, pathNodes, visited);
149
249
150
250
#ifdef DEBUG_PLOT
151
- ROS_INFO (" Current grid after first spiral is" );
152
- printGrid (grid, visited, fullPath);
153
- ROS_INFO (" There are %d goals remaining" , goals.size ());
251
+ ROS_INFO (" Visited grid updated after spiral:" );
252
+ printGrid (grid, visited, pathNodes, SpiralStart, pathNodes.back ());
154
253
#endif
155
- while (goals.size () != 0 )
156
- {
254
+
255
+ goals = map_2_goals (visited, eNodeOpen); // Retrieve remaining goalpoints
256
+
257
+ for (it = pathNodes.begin (); it != pathNodes.end (); ++it)
258
+ {
259
+ Point_t newPoint = { it->pos .x , it->pos .y };
260
+ visited_counter++;
261
+ fullPath.push_back (newPoint);
262
+ }
263
+
157
264
// Remove all elements from pathNodes list except last element.
158
265
// The last point is the starting point for a new search and A* extends the path from there on
159
266
pathNodes.erase (pathNodes.begin (), --(pathNodes.end ()));
@@ -189,23 +296,7 @@ std::list<Point_t> SpiralSTC::spiral_stc(std::vector<std::vector<bool> > const&
189
296
gridNode_t SpiralStart = pathNodes.back ();
190
297
printGrid (grid, visited, pathNodes, pathNodes.front (), pathNodes.back ());
191
298
#endif
192
-
193
- // Spiral fill from current position
194
- pathNodes = spiral (grid, pathNodes, visited);
195
-
196
- #ifdef DEBUG_PLOT
197
- ROS_INFO (" Visited grid updated after spiral:" );
198
- printGrid (grid, visited, pathNodes, SpiralStart, pathNodes.back ());
199
- #endif
200
-
201
- goals = map_2_goals (visited, eNodeOpen); // Retrieve remaining goalpoints
202
-
203
- for (it = pathNodes.begin (); it != pathNodes.end (); ++it)
204
- {
205
- Point_t newPoint = { it->pos .x , it->pos .y };
206
- visited_counter++;
207
- fullPath.push_back (newPoint);
208
- }
299
+
209
300
}
210
301
211
302
return fullPath;
0 commit comments