roadmap-1.cc 12.7 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
// Copyright (C) 2014 LAAS-CNRS
// Author: Mathieu Geisert
//
// This file is part of the hpp-core.
//
// hpp-core is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// test-hpp is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
// GNU Lesser General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public License
// along with hpp-core.  If not, see <http://www.gnu.org/licenses/>.

#include <boost/assign.hpp>

#include <hpp/util/debug.hh>
22
23
#include <hpp/pinocchio/device.hh>
#include <hpp/pinocchio/joint.hh>
Pierre Fernbach's avatar
Pierre Fernbach committed
24
#include <hpp/pinocchio/configuration.hh>
25
#include <hpp/pinocchio/urdf/util.hh>
26
27
#include <hpp/core/fwd.hh>
#include <hpp/core/roadmap.hh>
Joseph Mirabel's avatar
Joseph Mirabel committed
28
#include <hpp/core/problem.hh>
29
30
31
#include <hpp/core/weighed-distance.hh>
#include <hpp/core/connected-component.hh>
#include <hpp/core/node.hh>
Joseph Mirabel's avatar
Joseph Mirabel committed
32
#include <hpp/core/nearest-neighbor.hh>
33

34
#include <hpp/core/steering-method/straight.hh>
35
#include <hpp/core/weighed-distance.hh>
36

37
38
39
#define BOOST_TEST_MODULE roadmap-1
#include <boost/test/included/unit_test.hpp>

Pierre Fernbach's avatar
Pierre Fernbach committed
40
using namespace hpp::core;
41
42
using namespace hpp::pinocchio;

43
44
using hpp::core::steeringMethod::Straight;
using hpp::core::steeringMethod::StraightPtr_t;
45
46
47

BOOST_AUTO_TEST_SUITE( test_hpp_core )

48
49
50
51
52
53
54
55
56
void addEdge (const hpp::core::RoadmapPtr_t& r,
	      const hpp::core::SteeringMethod& sm,
	      const std::vector <NodePtr_t>& nodes,
	      std::size_t i, std::size_t j)
{
  r->addEdge (nodes [i], nodes [j], sm (*(nodes [i]->configuration ()),
					*(nodes [j]->configuration ())));
}

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
DevicePtr_t createRobot ()
{
  std::string urdf ("<robot name='test'>"
      "<link name='link1'/>"
      "<link name='link2'/>"
      "<link name='link3'/>"
      "<joint name='tx' type='prismatic'>"
        "<parent link='link1'/>"
        "<child  link='link2'/>"
        "<limit effort='30' velocity='1.0' lower='-3' upper='3'/>"
      "</joint>"
      "<joint name='ty' type='prismatic'>"
        "<axis xyz='0 1 0'/>"
        "<parent link='link2'/>"
        "<child  link='link3'/>"
        "<limit effort='30' velocity='1.0' lower='-3' upper='3'/>"
      "</joint>"
      "</robot>"
      );

  DevicePtr_t robot = Device::create ("test");
  urdf::loadModelFromString (robot, 0, "", "anchor", urdf, "");
  return robot;
}

82
83
BOOST_AUTO_TEST_CASE (Roadmap1) {
  // Build robot
84
  DevicePtr_t robot = createRobot();
85

86
  // Create steering method
87
  Problem p (robot);
88
  StraightPtr_t sm = Straight::create (p);
89
  // create roadmap
90
  hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
Joseph Mirabel's avatar
Joseph Mirabel committed
91
				     (robot, vector_t::Ones(2)));
Florent Lamiraux's avatar
Florent Lamiraux committed
92
  RoadmapPtr_t r = Roadmap::create (distance, robot);
93
94
95
96
97
98

  std::vector <NodePtr_t> nodes;

  // nodes [0]
  ConfigurationPtr_t q (new Configuration_t (robot->configSize ()));
  (*q) [0] = 0; (*q) [1] = 0;
99
  // Set init node
100
101
  r->initNode (q);
  nodes.push_back (r->initNode ());
102

103
104
105
106
  // nodes [1]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 1; (*q) [1] = 0;
  nodes.push_back (r->addNode (q));
107

108
109
110
111
  // nodes [2]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 0.5; (*q) [1] = 0.9;
  nodes.push_back (r->addNode (q));
112

113
114
115
116
  // nodes [3]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = -0.1; (*q) [1] = -0.9;
  nodes.push_back (r->addNode (q));
117

118
119
120
121
  // nodes [4]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 1.5; (*q) [1] = 2.9;
  nodes.push_back (r->addNode (q));
122

123
124
125
126
127
  // nodes [5]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 2.5; (*q) [1] = 2.9;
  nodes.push_back (r->addNode (q));
  r->addGoalNode (nodes [5]->configuration ());
128

129
  BOOST_MESSAGE(*r);
130
131
132
133
134
135
136
137
138
139
140
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 6);
  for (std::size_t i=0; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
  // 0 -> 1
141
  addEdge (r, *sm, nodes, 0, 1);
142
143
144
145
146
147
148
149
150
151
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 6);
  for (std::size_t i=0; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
152
  BOOST_MESSAGE(*r);
153

154
  // 1 -> 0
155
  addEdge (r, *sm, nodes, 1, 0);
156

157
158
159
160
161
162
163
164
165
166
167
168
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 5);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  for (std::size_t i=1; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
169
  BOOST_MESSAGE(*r);
170
  // 1 -> 2
171
  addEdge (r, *sm, nodes, 1, 2);
172
173
174
175
176
177
178
179
180
181
182
183
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 5);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  for (std::size_t i=1; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
184
  BOOST_MESSAGE(*r);
185
186

  // 2 -> 0
187
  addEdge (r, *sm, nodes, 2, 0);
188
189
190
191
192
193
194
195
196
197
198
199
200
201
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 4);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  for (std::size_t i=2; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
202
  BOOST_MESSAGE(*r);
203
204

  // 2 -> 3
205
  addEdge (r, *sm, nodes, 2, 3);
206
207
208
209
210
211
212
213
214
215
216
217
218
219
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 4);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  for (std::size_t i=2; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
220
  BOOST_MESSAGE(*r);
221
222

  // 2 -> 4
223
  addEdge (r, *sm, nodes, 2, 4);
224
225
226
227
228
229
230
231
232
233
234
235
236
237
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 4);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  for (std::size_t i=2; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (!r->pathExists ());
238
  BOOST_MESSAGE(*r);
239
240

  // 3 -> 5
241
  addEdge (r, *sm, nodes, 3, 5);
242
243
244
245
246
247
248
249
250
251
252
253
254
255
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 4);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  for (std::size_t i=2; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
  BOOST_CHECK (r->pathExists ());
256
  BOOST_MESSAGE(*r);
257
258

  // 4 -> 5
259
  addEdge (r, *sm, nodes, 4, 5);
260
261
262
263
264
265
266
267
268
269
270
271
272
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 4);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  for (std::size_t i=2; i < nodes.size (); ++i) {
    for (std::size_t j=i+1; j < nodes.size (); ++j) {
      BOOST_CHECK_MESSAGE (nodes [i]->connectedComponent () !=
			   nodes [j]->connectedComponent (),
			   "nodes " << i << " and " << j << "are in the same"
			   << " connected component");
    }
  }
273
  BOOST_CHECK (r->pathExists ());
274
  BOOST_MESSAGE(*r);
275
276

  // 5 -> 0
277
  addEdge (r, *sm, nodes, 5, 0);
278
279
280
281
282
283
284
285
286
287
288
289
  BOOST_CHECK_EQUAL (r->connectedComponents ().size (), 1);
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [1]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [2]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [3]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [4]->connectedComponent ());
  BOOST_CHECK (nodes [0]->connectedComponent () == 
	       nodes [5]->connectedComponent ());
  BOOST_CHECK (r->pathExists ());
290
  BOOST_MESSAGE(*r);
291

292
293
294
295
296
297
298
299
300
301
302
  // Check that memory if well deallocated.
  std::set<ConnectedComponentWkPtr_t> ccs;
  for (ConnectedComponents_t::const_iterator _cc = r->connectedComponents().begin();
      _cc != r->connectedComponents().end(); ++_cc)
    ccs.insert(*_cc);

  r.reset();
  for (std::set<ConnectedComponentWkPtr_t>::const_iterator _cc = ccs.begin();
      _cc != ccs.begin(); ++_cc) {
    BOOST_CHECK (! _cc->lock());
  }
303
}
304
305
306

BOOST_AUTO_TEST_CASE (nearestNeighbor) {
  // Build robot
307
  DevicePtr_t robot = createRobot();
308

309
310
  // Create steering method
  Problem p (robot);
311
  StraightPtr_t sm = Straight::create (p);
312
  // create roadmap
313
  hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
Joseph Mirabel's avatar
Joseph Mirabel committed
314
				     (robot, vector_t::Ones(2)));
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
  RoadmapPtr_t r = Roadmap::create (distance, robot);

  std::vector <NodePtr_t> nodes;

  // nodes [0]
  ConfigurationPtr_t q (new Configuration_t (robot->configSize ()));
  (*q) [0] = 0; (*q) [1] = 0;
  nodes.push_back (r->addNode (q));

  // nodes [1]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 1; (*q) [1] = 0;
  nodes.push_back (r->addNode (q));

  // nodes [2]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 0.5; (*q) [1] = 0.9;
  nodes.push_back (r->addNode (q));

  // nodes [3]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = -0.1; (*q) [1] = -0.9;
  nodes.push_back (r->addNode (q));

  // nodes [4]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 1.5; (*q) [1] = 2.9;
  nodes.push_back (r->addNode (q));

  // nodes [5]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 2.5; (*q) [1] = 2.9;
  nodes.push_back (r->addNode (q));
  r->addGoalNode (nodes [5]->configuration ());

  // nodes [6]
  q = ConfigurationPtr_t (new Configuration_t (robot->configSize ()));
  (*q) [0] = 0; (*q) [1] = 0.2;
  nodes.push_back (r->addNode (q));
  r->addGoalNode (nodes [6]->configuration ());

  // 0 -> 1
  addEdge (r, *sm, nodes, 0, 1);
  // 1 -> 0
  addEdge (r, *sm, nodes, 1, 0);
  // 1 -> 2
  addEdge (r, *sm, nodes, 1, 2);
  // 2 -> 0
  addEdge (r, *sm, nodes, 2, 0);
  // 0 -> 3
  addEdge (r, *sm, nodes, 0, 3);
  // 3 -> 2
  addEdge (r, *sm, nodes, 3, 2);

369
  hpp::pinocchio::value_type dist;
370
371
372
373
  using hpp::core::Nodes_t;
  Nodes_t knearest = r->nearestNeighbor()->KnearestSearch
    (nodes[0]->configuration(), nodes[0]->connectedComponent (), 3, dist);
  for (Nodes_t::const_iterator it = knearest.begin (); it != knearest.end(); ++it) {
374
    BOOST_TEST_MESSAGE ("q = [" << (*it)->configuration()->transpose() << "] - dist : " << (*distance) (*nodes[0]->configuration(), *(*it)->configuration()));
375
376
377
  }
  for (std::vector<NodePtr_t>::const_iterator it = nodes.begin (); it != nodes.end(); ++it) {
    Configuration_t& q = *(*it)->configuration();
378
    BOOST_TEST_MESSAGE ("[" << q.transpose() << "] - dist : " << (*distance) (*nodes[0]->configuration(), q));
379
380
  }
}
381
382
383
384
BOOST_AUTO_TEST_SUITE_END()