roadmap-1.cc 15.5 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
#include <hpp/pinocchio/serialization.hh>
27
28
#include <hpp/core/fwd.hh>
#include <hpp/core/roadmap.hh>
Joseph Mirabel's avatar
Joseph Mirabel committed
29
#include <hpp/core/problem.hh>
30
31
32
#include <hpp/core/weighed-distance.hh>
#include <hpp/core/connected-component.hh>
#include <hpp/core/node.hh>
Joseph Mirabel's avatar
Joseph Mirabel committed
33
#include <hpp/core/nearest-neighbor.hh>
34

35
#include <hpp/core/steering-method/straight.hh>
36
#include <hpp/core/weighed-distance.hh>
37
#include <hpp/core/parser/roadmap.hh>
38

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

Pierre Fernbach's avatar
Pierre Fernbach committed
42
using namespace hpp::core;
43
44
using namespace hpp::pinocchio;

45
46
using hpp::core::steeringMethod::Straight;
using hpp::core::steeringMethod::StraightPtr_t;
47
48
49

BOOST_AUTO_TEST_SUITE( test_hpp_core )

50
51
52
53
54
55
56
57
58
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 ())));
}

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
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;
}

84
85
BOOST_AUTO_TEST_CASE (Roadmap1) {
  // Build robot
86
  DevicePtr_t robot = createRobot();
87

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

  std::vector <NodePtr_t> nodes;

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

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

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

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

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

125
126
127
128
129
  // 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 ());
130

131
  BOOST_TEST_MESSAGE(*r);
132
133
134
135
136
137
138
139
140
141
142
  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
143
  addEdge (r, *sm, nodes, 0, 1);
144
145
146
147
148
149
150
151
152
153
  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 ());
154
  BOOST_TEST_MESSAGE(*r);
155

156
  // 1 -> 0
157
  addEdge (r, *sm, nodes, 1, 0);
158

159
160
161
162
163
164
165
166
167
168
169
170
  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 ());
171
  BOOST_TEST_MESSAGE(*r);
172
  // 1 -> 2
173
  addEdge (r, *sm, nodes, 1, 2);
174
175
176
177
178
179
180
181
182
183
184
185
  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 ());
186
  BOOST_TEST_MESSAGE(*r);
187
188

  // 2 -> 0
189
  addEdge (r, *sm, nodes, 2, 0);
190
191
192
193
194
195
196
197
198
199
200
201
202
203
  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 ());
204
  BOOST_TEST_MESSAGE(*r);
205
206

  // 2 -> 3
207
  addEdge (r, *sm, nodes, 2, 3);
208
209
210
211
212
213
214
215
216
217
218
219
220
221
  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 ());
222
  BOOST_TEST_MESSAGE(*r);
223
224

  // 2 -> 4
225
  addEdge (r, *sm, nodes, 2, 4);
226
227
228
229
230
231
232
233
234
235
236
237
238
239
  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 ());
240
  BOOST_TEST_MESSAGE(*r);
241
242

  // 3 -> 5
243
  addEdge (r, *sm, nodes, 3, 5);
244
245
246
247
248
249
250
251
252
253
254
255
256
257
  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 ());
258
  BOOST_TEST_MESSAGE(*r);
259
260

  // 4 -> 5
261
  addEdge (r, *sm, nodes, 4, 5);
262
263
264
265
266
267
268
269
270
271
272
273
274
  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");
    }
  }
275
  BOOST_CHECK (r->pathExists ());
276
  BOOST_TEST_MESSAGE(*r);
277
278

  // 5 -> 0
279
  addEdge (r, *sm, nodes, 5, 0);
280
281
282
283
284
285
286
287
288
289
290
291
  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 ());
292
  BOOST_TEST_MESSAGE(*r);
293

294
295
296
297
298
299
300
301
302
303
304
  // 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());
  }
305
}
306
307
308

BOOST_AUTO_TEST_CASE (nearestNeighbor) {
  // Build robot
309
  DevicePtr_t robot = createRobot();
310

311
  // Create steering method
Joseph Mirabel's avatar
Joseph Mirabel committed
312
  ProblemPtr_t p = Problem::create(robot);
313
  StraightPtr_t sm = Straight::create(p);
314
  // create roadmap
315
  hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
Joseph Mirabel's avatar
Joseph Mirabel committed
316
				     (robot, vector_t::Ones(2)));
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
369
370
  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);

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

384
385
386
387
388
389
BOOST_AUTO_TEST_CASE (serialization) {
  // Build robot
  DevicePtr_t robot = createRobot();

  // Create steering method
  ProblemPtr_t p = Problem::create(robot);
390
  StraightPtr_t sm = Straight::create(p);
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
  // create roadmap
  hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
				     (robot, vector_t::Ones(2)));
  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;
  // Set init node
  r->initNode (q);
  nodes.push_back (r->initNode ());

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

410
411
412
413
414
415
416
417
418
  // 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));
419

420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
  // 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 ());

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

  std::cout << *r << std::endl;

  // save data to archive
445
446
  parser::serializeRoadmap<hpp::serialization::text_oarchive>(r, "filename.txt", 
     parser::make_nvp(robot->name(), robot.get()));
447

448
449
  parser::serializeRoadmap<hpp::serialization::xml_oarchive>(r, "filename.xml", 
     parser::make_nvp(robot->name(), robot.get()));
450

451
452
  parser::serializeRoadmap<hpp::serialization::binary_oarchive>(r, "filename.bin", 
     parser::make_nvp(robot->name(), robot.get()));
453
454
455
}

BOOST_AUTO_TEST_CASE (deserialization) {
456
  DevicePtr_t robot = createRobot();
457
458

  RoadmapPtr_t nr;
459
460
461
462
463
464
465
466
467
468
469
  parser::serializeRoadmap<hpp::serialization::text_iarchive>(nr, "filename.txt", 
     parser::make_nvp(robot->name(), robot.get()));
  std::cout << *nr << std::endl;

  parser::serializeRoadmap<hpp::serialization::xml_iarchive>(nr, "filename.xml", 
     parser::make_nvp(robot->name(), robot.get()));
  std::cout << *nr << std::endl;

  parser::serializeRoadmap<hpp::serialization::binary_iarchive>(nr, "filename.bin", 
     parser::make_nvp(robot->name(), robot.get()));
  std::cout << *nr << std::endl;
470
471
472
}

BOOST_AUTO_TEST_SUITE_END()