-
Notifications
You must be signed in to change notification settings - Fork 547
/
model_based_planning_context.cpp
974 lines (887 loc) · 36.1 KB
/
model_based_planning_context.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
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
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
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
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
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include <boost/algorithm/string/trim.hpp>
#include <boost/algorithm/string/split.hpp>
#include <moveit/ompl_interface/model_based_planning_context.h>
#include <moveit/ompl_interface/detail/state_validity_checker.h>
#include <moveit/ompl_interface/detail/constrained_sampler.h>
#include <moveit/ompl_interface/detail/constrained_goal_sampler.h>
#include <moveit/ompl_interface/detail/goal_union.h>
#include <moveit/ompl_interface/detail/projection_evaluators.h>
#include <moveit/ompl_interface/detail/constraints_library.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/profiler/profiler.h>
#include <moveit/utils/lexical_casts.h>
#include <ompl/config.h>
#include <ompl/base/samplers/UniformValidStateSampler.h>
#include <ompl/base/goals/GoalLazySamples.h>
#include <ompl/tools/config/SelfConfig.h>
#include <ompl/base/spaces/SE3StateSpace.h>
#include <ompl/datastructures/PDF.h>
#include <ompl/base/terminationconditions/IterationTerminationCondition.h>
#include <ompl/base/terminationconditions/CostConvergenceTerminationCondition.h>
#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
#include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"
#include "ompl/base/objectives/MinimaxObjective.h"
#include "ompl/base/objectives/StateCostIntegralObjective.h"
#include "ompl/base/objectives/MaximizeMinClearanceObjective.h"
#include <ompl/geometric/planners/prm/LazyPRM.h>
namespace ompl_interface
{
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.model_based_planning_context");
} // namespace ompl_interface
ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext(const std::string& name,
const ModelBasedPlanningContextSpecification& spec)
: planning_interface::PlanningContext(name, spec.state_space_->getJointModelGroup()->getName())
, spec_(spec)
, complete_initial_robot_state_(spec.state_space_->getRobotModel())
, ompl_simple_setup_(spec.ompl_simple_setup_)
, ompl_benchmark_(*ompl_simple_setup_)
, ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition())
, ptc_(nullptr)
, last_plan_time_(0.0)
, last_simplify_time_(0.0)
, max_goal_samples_(0)
, max_state_sampling_attempts_(0)
, max_goal_sampling_attempts_(0)
, max_planning_threads_(0)
, max_solution_segment_length_(0.0)
, minimum_waypoint_count_(0)
, multi_query_planning_enabled_(false) // maintain "old" behavior by default
, simplify_solutions_(true)
, interpolate_(true)
, hybridize_(true)
{
complete_initial_robot_state_.setToDefaultValues(); // avoid uninitialized memory
complete_initial_robot_state_.update();
constraints_library_ = std::make_shared<ConstraintsLibrary>(this);
}
void ompl_interface::ModelBasedPlanningContext::configure(const rclcpp::Node::SharedPtr& node,
bool use_constraints_approximations)
{
loadConstraintApproximations(node);
if (!use_constraints_approximations)
{
setConstraintsApproximations(ConstraintsLibraryPtr());
}
complete_initial_robot_state_.update();
ompl_simple_setup_->getStateSpace()->computeSignature(space_signature_);
ompl_simple_setup_->getStateSpace()->setStateSamplerAllocator(
std::bind(&ModelBasedPlanningContext::allocPathConstrainedSampler, this, std::placeholders::_1));
if (spec_.constrained_state_space_)
{
// convert the input state to the corresponding OMPL state
ompl::base::ScopedState<> ompl_start_state(spec_.constrained_state_space_);
spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
ompl_simple_setup_->setStartState(ompl_start_state);
ompl_simple_setup_->setStateValidityChecker(
ob::StateValidityCheckerPtr(std::make_shared<ConstrainedPlanningStateValidityChecker>(this)));
}
else
{
// convert the input state to the corresponding OMPL state
ompl::base::ScopedState<> ompl_start_state(spec_.state_space_);
spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
ompl_simple_setup_->setStartState(ompl_start_state);
ompl_simple_setup_->setStateValidityChecker(std::make_shared<StateValidityChecker>(this));
}
if (path_constraints_ && constraints_library_)
{
const ConstraintApproximationPtr& constraint_approx =
constraints_library_->getConstraintApproximation(path_constraints_msg_);
if (constraint_approx)
{
getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
RCLCPP_INFO(LOGGER, "Using precomputed interpolation states");
}
}
useConfig();
if (ompl_simple_setup_->getGoal())
ompl_simple_setup_->setup();
}
void ompl_interface::ModelBasedPlanningContext::setProjectionEvaluator(const std::string& peval)
{
if (!spec_.state_space_)
{
RCLCPP_ERROR(LOGGER, "No state space is configured yet");
return;
}
ob::ProjectionEvaluatorPtr projection_eval = getProjectionEvaluator(peval);
if (projection_eval)
spec_.state_space_->registerDefaultProjection(projection_eval);
}
ompl::base::ProjectionEvaluatorPtr
ompl_interface::ModelBasedPlanningContext::getProjectionEvaluator(const std::string& peval) const
{
if (peval.find_first_of("link(") == 0 && peval[peval.length() - 1] == ')')
{
std::string link_name = peval.substr(5, peval.length() - 6);
if (getRobotModel()->hasLinkModel(link_name))
return ob::ProjectionEvaluatorPtr(new ProjectionEvaluatorLinkPose(this, link_name));
else
RCLCPP_ERROR(LOGGER,
"Attempted to set projection evaluator with respect to position of link '%s', "
"but that link is not known to the kinematic model.",
link_name.c_str());
}
else if (peval.find_first_of("joints(") == 0 && peval[peval.length() - 1] == ')')
{
std::string joints = peval.substr(7, peval.length() - 8);
boost::replace_all(joints, ",", " ");
std::vector<unsigned int> j;
std::stringstream ss(joints);
while (ss.good() && !ss.eof())
{
std::string joint;
ss >> joint >> std::ws;
if (getJointModelGroup()->hasJointModel(joint))
{
unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
if (variable_count > 0)
{
int idx = getJointModelGroup()->getVariableGroupIndex(joint);
for (unsigned int q = 0; q < variable_count; ++q)
{
j.push_back(idx + q);
}
}
else
{
RCLCPP_WARN(LOGGER, "%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(), joint.c_str());
}
}
else
{
RCLCPP_ERROR(LOGGER,
"%s: Attempted to set projection evaluator with respect to value of joint "
"'%s', but that joint is not known to the group '%s'.",
name_.c_str(), joint.c_str(), getGroupName().c_str());
}
}
if (j.empty())
{
RCLCPP_ERROR(LOGGER, "%s: No valid joints specified for joint projection", name_.c_str());
}
else
{
return ob::ProjectionEvaluatorPtr(new ProjectionEvaluatorJointValue(this, j));
}
}
else
{
RCLCPP_ERROR(LOGGER, "Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
}
return ob::ProjectionEvaluatorPtr();
}
ompl::base::StateSamplerPtr
ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler(const ompl::base::StateSpace* state_space) const
{
if (spec_.state_space_.get() != state_space)
{
RCLCPP_ERROR(LOGGER, "%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
return ompl::base::StateSamplerPtr();
}
RCLCPP_DEBUG(LOGGER, "%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
if (path_constraints_)
{
if (constraints_library_)
{
const ConstraintApproximationPtr& constraint_approx =
constraints_library_->getConstraintApproximation(path_constraints_msg_);
if (constraint_approx)
{
ompl::base::StateSamplerAllocator state_sampler_allocator =
constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
if (state_sampler_allocator)
{
ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
if (state_sampler)
{
RCLCPP_INFO(LOGGER,
"%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
name_.c_str(), path_constraints_msg_.name.c_str());
return state_sampler;
}
}
}
}
constraint_samplers::ConstraintSamplerPtr constraint_sampler;
if (spec_.constraint_sampler_manager_)
constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
path_constraints_->getAllConstraints());
if (constraint_sampler)
{
RCLCPP_INFO(LOGGER, "%s: Allocating specialized state sampler for state space", name_.c_str());
return ob::StateSamplerPtr(new ConstrainedSampler(this, constraint_sampler));
}
}
RCLCPP_DEBUG(LOGGER, "%s: Allocating default state sampler for state space", name_.c_str());
return state_space->allocDefaultStateSampler();
}
void ompl_interface::ModelBasedPlanningContext::useConfig()
{
const std::map<std::string, std::string>& config = spec_.config_;
if (config.empty())
return;
std::map<std::string, std::string> cfg = config;
// set the distance between waypoints when interpolating and collision checking.
auto it = cfg.find("longest_valid_segment_fraction");
// If one of the two variables is set.
if (it != cfg.end() || max_solution_segment_length_ != 0.0)
{
// clang-format off
double longest_valid_segment_fraction_config = (it != cfg.end())
? moveit::core::toDouble(it->second) // value from config file if there
: 0.01; // default value in OMPL.
double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
if (max_solution_segment_length_ > 0.0)
{
// If this parameter is specified too, take the most conservative of the two variables,
// i.e. the one that uses the shorter segment length.
longest_valid_segment_fraction_final = std::min(
longest_valid_segment_fraction_config,
max_solution_segment_length_ / spec_.state_space_->getMaximumExtent()
);
}
// clang-format on
// convert to string using no locale
cfg["longest_valid_segment_fraction"] = moveit::core::toString(longest_valid_segment_fraction_final);
}
// set the projection evaluator
it = cfg.find("projection_evaluator");
if (it != cfg.end())
{
setProjectionEvaluator(boost::trim_copy(it->second));
cfg.erase(it);
}
if (cfg.empty())
{
return;
}
std::string optimizer;
ompl::base::OptimizationObjectivePtr objective;
it = cfg.find("optimization_objective");
if (it != cfg.end())
{
optimizer = it->second;
cfg.erase(it);
if (optimizer == "PathLengthOptimizationObjective")
{
objective.reset(new ompl::base::PathLengthOptimizationObjective(ompl_simple_setup_->getSpaceInformation()));
}
else if (optimizer == "MinimaxObjective")
{
objective.reset(new ompl::base::MinimaxObjective(ompl_simple_setup_->getSpaceInformation()));
}
else if (optimizer == "StateCostIntegralObjective")
{
objective.reset(new ompl::base::StateCostIntegralObjective(ompl_simple_setup_->getSpaceInformation()));
}
else if (optimizer == "MechanicalWorkOptimizationObjective")
{
objective.reset(new ompl::base::MechanicalWorkOptimizationObjective(ompl_simple_setup_->getSpaceInformation()));
}
else if (optimizer == "MaximizeMinClearanceObjective")
{
objective.reset(new ompl::base::MaximizeMinClearanceObjective(ompl_simple_setup_->getSpaceInformation()));
}
else
{
objective.reset(new ompl::base::PathLengthOptimizationObjective(ompl_simple_setup_->getSpaceInformation()));
}
ompl_simple_setup_->setOptimizationObjective(objective);
}
// Don't clear planner data if multi-query planning is enabled
it = cfg.find("multi_query_planning_enabled");
if (it != cfg.end())
{
multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
}
// check whether the path returned by the planner should be interpolated
it = cfg.find("interpolate");
if (it != cfg.end())
{
interpolate_ = boost::lexical_cast<bool>(it->second);
cfg.erase(it);
}
// check whether solution paths from parallel planning should be hybridized
it = cfg.find("hybridize");
if (it != cfg.end())
{
hybridize_ = boost::lexical_cast<bool>(it->second);
cfg.erase(it);
}
// remove the 'type' parameter; the rest are parameters for the planner itself
it = cfg.find("type");
if (it == cfg.end())
{
if (name_ != getGroupName())
RCLCPP_WARN(LOGGER, "%s: Attribute 'type' not specified in planner configuration", name_.c_str());
}
else
{
std::string type = it->second;
cfg.erase(it);
const std::string planner_name = getGroupName() + "/" + name_;
ompl_simple_setup_->setPlannerAllocator(
std::bind(spec_.planner_selector_(type), std::placeholders::_1, planner_name, std::cref(spec_)));
RCLCPP_INFO(LOGGER,
"Planner configuration '%s' will use planner '%s'. "
"Additional configuration parameters will be set when the planner is constructed.",
name_.c_str(), type.c_str());
}
// call the setParams() after setup(), so we know what the params are
ompl_simple_setup_->getSpaceInformation()->setup();
ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg, true);
// call setup() again for possibly new param values
ompl_simple_setup_->getSpaceInformation()->setup();
}
void ompl_interface::ModelBasedPlanningContext::setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters& wparams)
{
if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
{
RCLCPP_WARN(LOGGER, "It looks like the planning volume was not specified.");
}
RCLCPP_DEBUG(LOGGER,
"%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = "
"[%f, %f], z = [%f, %f]",
name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
wparams.min_corner.z, wparams.max_corner.z);
spec_.state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
}
void ompl_interface::ModelBasedPlanningContext::simplifySolution(double timeout)
{
ompl_simple_setup_->simplifySolution(timeout);
last_simplify_time_ = ompl_simple_setup_->getLastSimplificationTime();
}
void ompl_interface::ModelBasedPlanningContext::interpolateSolution()
{
if (ompl_simple_setup_->haveSolutionPath())
{
og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
// Find the number of states that will be in the interpolated solution.
// This is what interpolate() does internally.
unsigned int eventual_states = 1;
std::vector<ompl::base::State*> states = pg.getStates();
for (size_t i = 0; i < states.size() - 1; i++)
{
eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
}
if (eventual_states < minimum_waypoint_count_)
{
// If that's not enough states, use the minimum amount instead.
pg.interpolate(minimum_waypoint_count_);
}
else
{
// Interpolate the path to have as the exact states that are checked when validating motions.
pg.interpolate();
}
}
}
void ompl_interface::ModelBasedPlanningContext::convertPath(const ompl::geometric::PathGeometric& pg,
robot_trajectory::RobotTrajectory& traj) const
{
moveit::core::RobotState ks = complete_initial_robot_state_;
for (std::size_t i = 0; i < pg.getStateCount(); ++i)
{
spec_.state_space_->copyToRobotState(ks, pg.getState(i));
traj.addSuffixWayPoint(ks, 0.0);
}
}
bool ompl_interface::ModelBasedPlanningContext::getSolutionPath(robot_trajectory::RobotTrajectory& traj) const
{
traj.clear();
if (ompl_simple_setup_->haveSolutionPath())
{
convertPath(ompl_simple_setup_->getSolutionPath(), traj);
}
return ompl_simple_setup_->haveSolutionPath();
}
void ompl_interface::ModelBasedPlanningContext::setVerboseStateValidityChecks(bool flag)
{
if (ompl_simple_setup_->getStateValidityChecker())
{
static_cast<StateValidityChecker*>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
}
}
ompl::base::GoalPtr ompl_interface::ModelBasedPlanningContext::constructGoal()
{
// ******************* set up the goal representation, based on goal constraints
std::vector<ob::GoalPtr> goals;
for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
{
constraint_samplers::ConstraintSamplerPtr constraint_sampler;
if (spec_.constraint_sampler_manager_)
{
constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
goal_constraint->getAllConstraints());
}
if (constraint_sampler)
{
ob::GoalPtr goal = ob::GoalPtr(new ConstrainedGoalSampler(this, goal_constraint, constraint_sampler));
goals.push_back(goal);
}
}
if (!goals.empty())
{
return goals.size() == 1 ? goals[0] : ompl::base::GoalPtr(new GoalSampleableRegionMux(goals));
}
else
{
RCLCPP_ERROR(LOGGER, "Unable to construct goal representation");
}
return ob::GoalPtr();
}
ompl::base::PlannerTerminationCondition
ompl_interface::ModelBasedPlanningContext::constructPlannerTerminationCondition(double timeout,
const ompl::time::point& start)
{
auto it = spec_.config_.find("termination_condition");
if (it == spec_.config_.end())
{
return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
}
std::string termination_string = it->second;
std::vector<std::string> termination_and_params;
boost::split(termination_and_params, termination_string, boost::is_any_of("[ ,]"));
if (termination_and_params.empty())
{
RCLCPP_ERROR(LOGGER, "Termination condition not specified");
}
// Terminate if a maximum number of iterations is exceeded or a timeout occurs.
// The semantics of "iterations" are planner-specific, but typically it corresponds to the number of times
// an attempt was made to grow a roadmap/tree.
else if (termination_and_params[0] == "Iteration")
{
if (termination_and_params.size() > 1)
{
return ob::plannerOrTerminationCondition(
ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
}
else
{
RCLCPP_ERROR(LOGGER, "Missing argument to Iteration termination condition");
}
}
// TODO: remove when ROS Melodic and older are no longer supported
#if OMPL_VERSION_VALUE >= 1005000
// Terminate if the cost has converged or a timeout occurs.
// Only useful for anytime/optimizing planners.
else if (termination_and_params[0] == "CostConvergence")
{
std::size_t solutions_window = 10u;
double epsilon = 0.1;
if (termination_and_params.size() > 1)
{
solutions_window = std::stoul(termination_and_params[1]);
if (termination_and_params.size() > 2)
{
epsilon = moveit::core::toDouble(termination_and_params[2]);
}
}
return ob::plannerOrTerminationCondition(
ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
ob::CostConvergenceTerminationCondition(ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon));
}
#endif
// Terminate as soon as an exact solution is found or a timeout occurs.
// This modifies the behavior of anytime/optimizing planners to terminate upon discovering
// the first feasible solution.
else if (termination_and_params[0] == "ExactSolution")
{
return ob::plannerOrTerminationCondition(
ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
}
else
{
RCLCPP_ERROR(LOGGER, "Unknown planner termination condition");
}
// return a planner termination condition to suppress compiler warning
return ob::plannerAlwaysTerminatingCondition();
}
void ompl_interface::ModelBasedPlanningContext::setCompleteInitialState(
const moveit::core::RobotState& complete_initial_robot_state)
{
complete_initial_robot_state_ = complete_initial_robot_state;
complete_initial_robot_state_.update();
}
void ompl_interface::ModelBasedPlanningContext::clear()
{
if (!multi_query_planning_enabled_)
{
ompl_simple_setup_->clear();
}
// TODO: remove when ROS Melodic and older are no longer supported
#if OMPL_VERSION_VALUE >= 1005000
else
{
// For LazyPRM and LazyPRMstar we assume that the environment *could* have changed
// This means that we need to reset the validity flags for every node and edge in
// the roadmap. For PRM and PRMstar we assume that the environment is static. If
// this is not the case, then multi-query planning should not be enabled.
auto planner = dynamic_cast<ompl::geometric::LazyPRM*>(ompl_simple_setup_->getPlanner().get());
if (planner != nullptr)
{
planner->clearValidity();
}
}
#endif
ompl_simple_setup_->clearStartStates();
ompl_simple_setup_->setGoal(ob::GoalPtr());
ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr());
path_constraints_.reset();
goal_constraints_.clear();
getOMPLStateSpace()->setInterpolationFunction(InterpolationFunction());
}
bool ompl_interface::ModelBasedPlanningContext::setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints,
moveit_msgs::msg::MoveItErrorCodes* /*error*/)
{
// ******************* set the path constraints to use
path_constraints_.reset(new kinematic_constraints::KinematicConstraintSet(getRobotModel()));
path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
path_constraints_msg_ = path_constraints;
return true;
}
bool ompl_interface::ModelBasedPlanningContext::setGoalConstraints(
const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
const moveit_msgs::msg::Constraints& path_constraints, moveit_msgs::msg::MoveItErrorCodes* error)
{
// ******************* check if the input is correct
goal_constraints_.clear();
for (const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
{
moveit_msgs::msg::Constraints constr = kinematic_constraints::mergeConstraints(goal_constraint, path_constraints);
kinematic_constraints::KinematicConstraintSetPtr kset(
new kinematic_constraints::KinematicConstraintSet(getRobotModel()));
kset->add(constr, getPlanningScene()->getTransforms());
if (!kset->empty())
{
goal_constraints_.push_back(kset);
}
}
if (goal_constraints_.empty())
{
RCLCPP_WARN(LOGGER, "%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
if (error)
{
error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
}
return false;
}
ob::GoalPtr goal = constructGoal();
ompl_simple_setup_->setGoal(goal);
return static_cast<bool>(goal);
}
bool ompl_interface::ModelBasedPlanningContext::benchmark(double timeout, unsigned int count,
const std::string& filename)
{
ompl_benchmark_.clearPlanners();
ompl_simple_setup_->setup();
ompl_benchmark_.addPlanner(ompl_simple_setup_->getPlanner());
ompl_benchmark_.setExperimentName(getRobotModel()->getName() + "_" + getGroupName() + "_" +
getPlanningScene()->getName() + "_" + name_);
ot::Benchmark::Request req;
req.maxTime = timeout;
req.runCount = count;
req.displayProgress = true;
req.saveConsoleOutput = false;
ompl_benchmark_.benchmark(req);
return filename.empty() ? ompl_benchmark_.saveResultsToFile() : ompl_benchmark_.saveResultsToFile(filename.c_str());
}
void ompl_interface::ModelBasedPlanningContext::startSampling()
{
bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
if (gls)
{
static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->startSampling();
}
else
{
// we know this is a GoalSampleableMux by elimination
static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->startSampling();
}
}
void ompl_interface::ModelBasedPlanningContext::stopSampling()
{
bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
if (gls)
{
static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->stopSampling();
}
else
{
// we know this is a GoalSampleableMux by elimination
static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->stopSampling();
}
}
void ompl_interface::ModelBasedPlanningContext::preSolve()
{
// clear previously computed solutions
ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
if (planner && !multi_query_planning_enabled_)
{
planner->clear();
}
startSampling();
ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
}
void ompl_interface::ModelBasedPlanningContext::postSolve()
{
stopSampling();
int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
RCLCPP_DEBUG(LOGGER, "There were %d valid motions and %d invalid motions.", v, iv);
if (ompl_simple_setup_->getProblemDefinition()->hasApproximateSolution())
{
RCLCPP_WARN(LOGGER, "Computed solution is approximate");
}
}
bool ompl_interface::ModelBasedPlanningContext::solve(planning_interface::MotionPlanResponse& res)
{
if (solve(request_.allowed_planning_time, request_.num_planning_attempts))
{
double ptime = getLastPlanTime();
if (simplify_solutions_)
{
simplifySolution(request_.allowed_planning_time - ptime);
ptime += getLastSimplifyTime();
}
if (interpolate_)
{
interpolateSolution();
}
// fill the response
RCLCPP_DEBUG(LOGGER, "%s: Returning successful solution with %lu states", getName().c_str(),
getOMPLSimpleSetup()->getSolutionPath().getStateCount());
res.trajectory_.reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
getSolutionPath(*res.trajectory_);
res.planning_time_ = ptime;
return true;
}
else
{
RCLCPP_INFO(LOGGER, "Unable to solve the planning problem");
res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
return false;
}
}
bool ompl_interface::ModelBasedPlanningContext::solve(planning_interface::MotionPlanDetailedResponse& res)
{
if (solve(request_.allowed_planning_time, request_.num_planning_attempts))
{
res.trajectory_.reserve(3);
// add info about planned solution
double ptime = getLastPlanTime();
res.processing_time_.push_back(ptime);
res.description_.emplace_back("plan");
res.trajectory_.resize(res.trajectory_.size() + 1);
res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
getSolutionPath(*res.trajectory_.back());
// simplify solution if time remains
if (simplify_solutions_)
{
simplifySolution(request_.allowed_planning_time - ptime);
res.processing_time_.push_back(getLastSimplifyTime());
res.description_.emplace_back("simplify");
res.trajectory_.resize(res.trajectory_.size() + 1);
res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
getSolutionPath(*res.trajectory_.back());
}
if (interpolate_)
{
ompl::time::point start_interpolate = ompl::time::now();
interpolateSolution();
res.processing_time_.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
res.description_.emplace_back("interpolate");
res.trajectory_.resize(res.trajectory_.size() + 1);
res.trajectory_.back().reset(new robot_trajectory::RobotTrajectory(getRobotModel(), getGroupName()));
getSolutionPath(*res.trajectory_.back());
}
// fill the response
RCLCPP_DEBUG(LOGGER, "%s: Returning successful solution with %lu states", getName().c_str(),
getOMPLSimpleSetup()->getSolutionPath().getStateCount());
return true;
}
else
{
RCLCPP_INFO(LOGGER, "Unable to solve the planning problem");
res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
return false;
}
}
bool ompl_interface::ModelBasedPlanningContext::solve(double timeout, unsigned int count)
{
moveit::tools::Profiler::ScopedBlock sblock("PlanningContext:Solve");
ompl::time::point start = ompl::time::now();
preSolve();
bool result = false;
if (count <= 1 || multi_query_planning_enabled_) // multi-query planners should always run in single instances
{
RCLCPP_DEBUG(LOGGER, "%s: Solving the planning problem once...", name_.c_str());
ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
registerTerminationCondition(ptc);
result = ompl_simple_setup_->solve(ptc) == ompl::base::PlannerStatus::EXACT_SOLUTION;
last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
unregisterTerminationCondition();
}
else
{
RCLCPP_DEBUG(LOGGER, "%s: Solving the planning problem %u times...", name_.c_str(), count);
ompl_parallel_plan_.clearHybridizationPaths();
if (count <= max_planning_threads_)
{
ompl_parallel_plan_.clearPlanners();
if (ompl_simple_setup_->getPlannerAllocator())
for (unsigned int i = 0; i < count; ++i)
{
ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
}
else
{
for (unsigned int i = 0; i < count; ++i)
{
ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
}
}
ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
registerTerminationCondition(ptc);
result = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
unregisterTerminationCondition();
}
else
{
ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
registerTerminationCondition(ptc);
int n = count / max_planning_threads_;
result = true;
for (int i = 0; i < n && !ptc(); ++i)
{
ompl_parallel_plan_.clearPlanners();
if (ompl_simple_setup_->getPlannerAllocator())
{
for (unsigned int i = 0; i < max_planning_threads_; ++i)
{
ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
}
}
else
{
for (unsigned int i = 0; i < max_planning_threads_; ++i)
{
ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
}
}
bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
result = result && r;
}
n = count % max_planning_threads_;
if (n && !ptc())
{
ompl_parallel_plan_.clearPlanners();
if (ompl_simple_setup_->getPlannerAllocator())
{
for (int i = 0; i < n; ++i)
{
ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
}
}
else
{
for (int i = 0; i < n; ++i)
{
ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
}
}
bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
result = result && r;
}
last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
unregisterTerminationCondition();
}
}
postSolve();
return result;
}
void ompl_interface::ModelBasedPlanningContext::registerTerminationCondition(const ob::PlannerTerminationCondition& ptc)
{
std::unique_lock<std::mutex> slock(ptc_lock_);
ptc_ = &ptc;
}
void ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition()
{
std::unique_lock<std::mutex> slock(ptc_lock_);
ptc_ = nullptr;
}
bool ompl_interface::ModelBasedPlanningContext::terminate()
{
std::unique_lock<std::mutex> slock(ptc_lock_);
if (ptc_)
{
ptc_->terminate();
}
return true;
}
bool ompl_interface::ModelBasedPlanningContext::saveConstraintApproximations(const rclcpp::Node::SharedPtr& node)
{
std::string constraint_path;
if (node->get_parameter("constraint_approximations_path", constraint_path))
{
constraints_library_->saveConstraintApproximations(constraint_path);
return true;
}
RCLCPP_WARN(LOGGER, "ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
return false;
}
bool ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations(const rclcpp::Node::SharedPtr& node)
{
std::string constraint_path;
if (node->get_parameter("constraint_approximations_path", constraint_path))
{
constraints_library_->loadConstraintApproximations(constraint_path);
std::stringstream ss;
constraints_library_->printConstraintApproximations(ss);
RCLCPP_INFO_STREAM(LOGGER, ss.str());
return true;
}
return false;
}