/
moveit_config_data.cpp
1776 lines (1544 loc) · 70.3 KB
/
moveit_config_data.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
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*********************************************************************
* 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: Dave Coleman */
#include <moveit/setup_assistant/tools/moveit_config_data.h>
// Reading/Writing Files
#include <iostream> // For writing yaml and launch files
#include <fstream>
#include <boost/filesystem.hpp> // for creating folders/files
#include <boost/algorithm/string.hpp> // for string find and replace in templates
// ROS
#include <ros/console.h>
#include <ros/package.h> // for getting file path for loading images
namespace moveit_setup_assistant
{
// File system
namespace fs = boost::filesystem;
// ******************************************************************************************
// Constructor
// ******************************************************************************************
MoveItConfigData::MoveItConfigData() : config_pkg_generated_timestamp_(0)
{
// Create an instance of SRDF writer and URDF model for all widgets to share
srdf_.reset(new srdf::SRDFWriter());
urdf_model_.reset(new urdf::Model());
// Not in debug mode
debug_ = false;
// Get MoveIt Setup Assistant package path
setup_assistant_path_ = ros::package::getPath("moveit_setup_assistant");
if (setup_assistant_path_.empty())
{
setup_assistant_path_ = ".";
}
}
// ******************************************************************************************
// Destructor
// ******************************************************************************************
MoveItConfigData::~MoveItConfigData()
{
}
// ******************************************************************************************
// Load a robot model
// ******************************************************************************************
void MoveItConfigData::setRobotModel(robot_model::RobotModelPtr robot_model)
{
robot_model_ = robot_model;
}
// ******************************************************************************************
// Provide a kinematic model. Load a new one if necessary
// ******************************************************************************************
robot_model::RobotModelConstPtr MoveItConfigData::getRobotModel()
{
if (!robot_model_)
{
// Initialize with a URDF Model Interface and a SRDF Model
robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
}
return robot_model_;
}
// ******************************************************************************************
// Update the Kinematic Model with latest SRDF modifications
// ******************************************************************************************
void MoveItConfigData::updateRobotModel()
{
ROS_INFO("Updating kinematic model");
// Tell SRDF Writer to create new SRDF Model, use original URDF model
srdf_->updateSRDFModel(*urdf_model_);
// Create new kin model
robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
// Reset the planning scene
planning_scene_.reset();
}
// ******************************************************************************************
// Provide a shared planning scene
// ******************************************************************************************
planning_scene::PlanningScenePtr MoveItConfigData::getPlanningScene()
{
if (!planning_scene_)
{
// make sure kinematic model exists
getRobotModel();
// Allocate an empty planning scene
planning_scene_.reset(new planning_scene::PlanningScene(robot_model_));
}
return planning_scene_;
}
// ******************************************************************************************
// Load the allowed collision matrix from the SRDF's list of link pairs
// ******************************************************************************************
void MoveItConfigData::loadAllowedCollisionMatrix()
{
// Clear the allowed collision matrix
allowed_collision_matrix_.clear();
// Update the allowed collision matrix, in case there has been a change
for (std::vector<srdf::Model::DisabledCollision>::const_iterator pair_it = srdf_->disabled_collisions_.begin();
pair_it != srdf_->disabled_collisions_.end(); ++pair_it)
{
allowed_collision_matrix_.setEntry(pair_it->link1_, pair_it->link2_, true);
}
}
// ******************************************************************************************
// Output MoveIt Setup Assistant hidden settings file
// ******************************************************************************************
bool MoveItConfigData::outputSetupAssistantFile(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
// Output every available planner ---------------------------------------------------
emitter << YAML::Key << "moveit_setup_assistant_config";
emitter << YAML::Value << YAML::BeginMap;
// URDF Path Location
emitter << YAML::Key << "URDF";
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "package" << YAML::Value << urdf_pkg_name_;
emitter << YAML::Key << "relative_path" << YAML::Value << urdf_pkg_relative_path_;
emitter << YAML::Key << "xacro_args" << YAML::Value << xacro_args_;
emitter << YAML::EndMap;
/// SRDF Path Location
emitter << YAML::Key << "SRDF";
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "relative_path" << YAML::Value << srdf_pkg_relative_path_;
emitter << YAML::EndMap;
/// Package generation time
emitter << YAML::Key << "CONFIG";
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "author_name" << YAML::Value << author_name_;
emitter << YAML::Key << "author_email" << YAML::Value << author_email_;
emitter << YAML::Key << "generated_timestamp" << YAML::Value << std::time(NULL); // TODO: is this cross-platform?
emitter << YAML::EndMap;
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Output OMPL Planning config files
// ******************************************************************************************
bool MoveItConfigData::outputOMPLPlanningYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
// Output every available planner ---------------------------------------------------
emitter << YAML::Key << "planner_configs";
emitter << YAML::Value << YAML::BeginMap;
std::vector<OMPLPlannerDescription> planner_des = getOMPLPlanners();
// Add Planners with parameter values
std::vector<std::string> pconfigs;
for (std::size_t i = 0; i < planner_des.size(); ++i)
{
std::string defaultconfig = planner_des[i].name_;
emitter << YAML::Key << defaultconfig;
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "type" << YAML::Value << "geometric::" + planner_des[i].name_;
for (std::size_t j = 0; j < planner_des[i].parameter_list_.size(); j++)
{
emitter << YAML::Key << planner_des[i].parameter_list_[j].name;
emitter << YAML::Value << planner_des[i].parameter_list_[j].value;
emitter << YAML::Comment(planner_des[i].parameter_list_[j].comment.c_str());
}
emitter << YAML::EndMap;
pconfigs.push_back(defaultconfig);
}
// End of every avail planner
emitter << YAML::EndMap;
// Output every group and the planners it can use ----------------------------------
for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
++group_it)
{
emitter << YAML::Key << group_it->name_;
emitter << YAML::Value << YAML::BeginMap;
// Output associated planners
emitter << YAML::Key << "default_planner_config" << YAML::Value
<< group_meta_data_[group_it->name_].default_planner_ + "kConfigDefault";
emitter << YAML::Key << "planner_configs";
emitter << YAML::Value << YAML::BeginSeq;
for (std::size_t i = 0; i < pconfigs.size(); ++i)
emitter << pconfigs[i] + "kConfigDefault";
emitter << YAML::EndSeq;
// Output projection_evaluator
std::string projection_joints = decideProjectionJoints(group_it->name_);
if (!projection_joints.empty())
{
emitter << YAML::Key << "projection_evaluator";
emitter << YAML::Value << projection_joints;
// OMPL collision checking discretization
emitter << YAML::Key << "longest_valid_segment_fraction";
emitter << YAML::Value << "0.005";
}
emitter << YAML::EndMap;
}
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Output CHOMP Planning config files
// ******************************************************************************************
bool MoveItConfigData::outputCHOMPPlanningYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "planning_time_limit" << YAML::Value << "10.0";
emitter << YAML::Key << "max_iterations" << YAML::Value << "200";
emitter << YAML::Key << "max_iterations_after_collision_free" << YAML::Value << "5";
emitter << YAML::Key << "smoothness_cost_weight" << YAML::Value << "0.1";
emitter << YAML::Key << "obstacle_cost_weight" << YAML::Value << "1.0";
emitter << YAML::Key << "learning_rate" << YAML::Value << "0.01";
emitter << YAML::Key << "smoothness_cost_velocity" << YAML::Value << "0.0";
emitter << YAML::Key << "smoothness_cost_acceleration" << YAML::Value << "1.0";
emitter << YAML::Key << "smoothness_cost_jerk" << YAML::Value << "0.0";
emitter << YAML::Key << "ridge_factor" << YAML::Value << "0.01";
emitter << YAML::Key << "use_pseudo_inverse" << YAML::Value << "false";
emitter << YAML::Key << "pseudo_inverse_ridge_factor" << YAML::Value << "1e-4";
emitter << YAML::Key << "joint_update_limit" << YAML::Value << "0.1";
emitter << YAML::Key << "collision_clearence" << YAML::Value << "0.2";
emitter << YAML::Key << "collision_threshold" << YAML::Value << "0.07";
emitter << YAML::Key << "use_stochastic_descent" << YAML::Value << "true";
emitter << YAML::Key << "enable_failure_recovery" << YAML::Value << "true";
emitter << YAML::Key << "max_recovery_attempts" << YAML::Value << "5";
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Output kinematic config files
// ******************************************************************************************
bool MoveItConfigData::outputKinematicsYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
// Output every group and the kinematic solver it can use ----------------------------------
for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
++group_it)
{
// Only save kinematic data if the solver is not "None"
if (group_meta_data_[group_it->name_].kinematics_solver_.empty() ||
group_meta_data_[group_it->name_].kinematics_solver_ == "None")
continue;
emitter << YAML::Key << group_it->name_;
emitter << YAML::Value << YAML::BeginMap;
// Kinematic Solver
emitter << YAML::Key << "kinematics_solver";
emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_;
// Search Resolution
emitter << YAML::Key << "kinematics_solver_search_resolution";
emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_search_resolution_;
// Solver Timeout
emitter << YAML::Key << "kinematics_solver_timeout";
emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_timeout_;
// Solver Attempts
emitter << YAML::Key << "kinematics_solver_attempts";
emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_attempts_;
emitter << YAML::EndMap;
}
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Writes a Gazebo compatible robot URDF to gazebo_compatible_urdf_string_
// ******************************************************************************************
std::string MoveItConfigData::getGazeboCompatibleURDF()
{
bool new_urdf_needed = false;
TiXmlDocument urdf_document;
// Used to convert XmlDocument to std string
TiXmlPrinter printer;
urdf_document.Parse((const char*)urdf_string_.c_str(), 0, TIXML_ENCODING_UTF8);
try
{
for (TiXmlElement* link_element = urdf_document.RootElement()->FirstChildElement(); link_element != NULL;
link_element = link_element->NextSiblingElement())
{
if (((std::string)link_element->Value()).find("link") == std::string::npos)
continue;
// Before adding inertial elements, make sure there is none and the link has collision element
if (link_element->FirstChildElement("inertial") == NULL && link_element->FirstChildElement("collision") != NULL)
{
new_urdf_needed = true;
TiXmlElement inertia_link("inertial");
TiXmlElement mass("mass");
TiXmlElement inertia_joint("inertia");
mass.SetAttribute("value", "0.1");
inertia_joint.SetAttribute("ixx", "0.03");
inertia_joint.SetAttribute("iyy", "0.03");
inertia_joint.SetAttribute("izz", "0.03");
inertia_joint.SetAttribute("ixy", "0.0");
inertia_joint.SetAttribute("ixz", "0.0");
inertia_joint.SetAttribute("iyz", "0.0");
inertia_link.InsertEndChild(mass);
inertia_link.InsertEndChild(inertia_joint);
link_element->InsertEndChild(inertia_link);
}
}
}
catch (YAML::ParserException& e) // Catch errors
{
ROS_ERROR_STREAM_NAMED("moveit_config_data", e.what());
return std::string("");
}
if (new_urdf_needed)
{
urdf_document.Accept(&printer);
return std::string(printer.CStr());
}
return std::string("");
}
bool MoveItConfigData::outputFakeControllersYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
emitter << YAML::Key << "controller_list";
emitter << YAML::Value << YAML::BeginSeq;
// Loop through groups
for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
++group_it)
{
// Get list of associated joints
const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
emitter << YAML::BeginMap;
const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
emitter << YAML::Key << "name";
emitter << YAML::Value << "fake_" + group_it->name_ + "_controller";
emitter << YAML::Key << "joints";
emitter << YAML::Value << YAML::BeginSeq;
// Iterate through the joints
for (const robot_model::JointModel* joint : joint_models)
{
if (joint->isPassive() || joint->getMimic() != NULL || joint->getType() == robot_model::JointModel::FIXED)
continue;
emitter << joint->getName();
}
emitter << YAML::EndSeq;
emitter << YAML::EndMap;
}
emitter << YAML::EndSeq;
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
std::vector<OMPLPlannerDescription> MoveItConfigData::getOMPLPlanners()
{
std::vector<OMPLPlannerDescription> planner_des;
OMPLPlannerDescription SBL("SBL", "geometric");
SBL.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
planner_des.push_back(SBL);
OMPLPlannerDescription EST("EST", "geometric");
EST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()");
EST.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
planner_des.push_back(EST);
OMPLPlannerDescription LBKPIECE("LBKPIECE", "geometric");
LBKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
LBKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
LBKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
planner_des.push_back(LBKPIECE);
OMPLPlannerDescription BKPIECE("BKPIECE", "geometric");
BKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
BKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
BKPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
"default: 0.5");
BKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
planner_des.push_back(BKPIECE);
OMPLPlannerDescription KPIECE("KPIECE", "geometric");
KPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
KPIECE.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
KPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9 (0.0,1.]");
KPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
"default: 0.5");
KPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
planner_des.push_back(KPIECE);
OMPLPlannerDescription RRT("RRT", "geometric");
RRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
RRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
planner_des.push_back(RRT);
OMPLPlannerDescription RRTConnect("RRTConnect", "geometric");
RRTConnect.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
planner_des.push_back(RRTConnect);
OMPLPlannerDescription RRTstar("RRTstar", "geometric");
RRTstar.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
RRTstar.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
RRTstar.addParameter("delay_collision_checking", "1", "Stop collision checking as soon as C-free parent found. "
"default 1");
planner_des.push_back(RRTstar);
OMPLPlannerDescription TRRT("TRRT", "geometric");
TRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
TRRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
TRRT.addParameter("max_states_failed", "10", "when to start increasing temp. default: 10");
TRRT.addParameter("temp_change_factor", "2.0", "how much to increase or decrease temp. default: 2.0");
TRRT.addParameter("min_temperature", "10e-10", "lower limit of temp change. default: 10e-10");
TRRT.addParameter("init_temperature", "10e-6", "initial temperature. default: 10e-6");
TRRT.addParameter("frountier_threshold", "0.0", "dist new state to nearest neighbor to disqualify as frontier. "
"default: 0.0 set in setup()");
TRRT.addParameter("frountierNodeRatio", "0.1", "1/10, or 1 nonfrontier for every 10 frontier. default: 0.1");
TRRT.addParameter("k_constant", "0.0", "value used to normalize expresssion. default: 0.0 set in setup()");
planner_des.push_back(TRRT);
OMPLPlannerDescription PRM("PRM", "geometric");
PRM.addParameter("max_nearest_neighbors", "10", "use k nearest neighbors. default: 10");
planner_des.push_back(PRM);
OMPLPlannerDescription PRMstar("PRMstar", "geometric"); // no declares in code
planner_des.push_back(PRMstar);
OMPLPlannerDescription FMT("FMT", "geometric");
FMT.addParameter("num_samples", "1000", "number of states that the planner should sample. default: 1000");
FMT.addParameter("radius_multiplier", "1.1", "multiplier used for the nearest neighbors search radius. default: 1.1");
FMT.addParameter("nearest_k", "1", "use Knearest strategy. default: 1");
FMT.addParameter("cache_cc", "1", "use collision checking cache. default: 1");
FMT.addParameter("heuristics", "0", "activate cost to go heuristics. default: 0");
FMT.addParameter("extended_fmt", "1", "activate the extended FMT*: adding new samples if planner does not finish "
"successfully. default: 1");
planner_des.push_back(FMT);
OMPLPlannerDescription BFMT("BFMT", "geometric");
BFMT.addParameter("num_samples", "1000", "number of states that the planner should sample. default: 1000");
BFMT.addParameter("radius_multiplier", "1.0", "multiplier used for the nearest neighbors search radius. default: "
"1.0");
BFMT.addParameter("nearest_k", "1", "use the Knearest strategy. default: 1");
BFMT.addParameter("balanced", "0", "exploration strategy: balanced true expands one tree every iteration. False will "
"select the tree with lowest maximum cost to go. default: 1");
BFMT.addParameter("optimality", "1", "termination strategy: optimality true finishes when the best possible path is "
"found. Otherwise, the algorithm will finish when the first feasible path is "
"found. default: 1");
BFMT.addParameter("heuristics", "1", "activates cost to go heuristics. default: 1");
BFMT.addParameter("cache_cc", "1", "use the collision checking cache. default: 1");
BFMT.addParameter("extended_fmt", "1", "Activates the extended FMT*: adding new samples if planner does not finish "
"successfully. default: 1");
planner_des.push_back(BFMT);
OMPLPlannerDescription PDST("PDST", "geometric");
RRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
planner_des.push_back(PDST);
OMPLPlannerDescription STRIDE("STRIDE", "geometric");
STRIDE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
STRIDE.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
STRIDE.addParameter("use_projected_distance", "0", "whether nearest neighbors are computed based on distances in a "
"projection of the state rather distances in the state space "
"itself. default: 0");
STRIDE.addParameter("degree", "16", "desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). "
"default: 16");
STRIDE.addParameter("max_degree", "18", "max degree of a node in the GNAT. default: 12");
STRIDE.addParameter("min_degree", "12", "min degree of a node in the GNAT. default: 12");
STRIDE.addParameter("max_pts_per_leaf", "6", "max points per leaf in the GNAT. default: 6");
STRIDE.addParameter("estimated_dimension", "0.0", "estimated dimension of the free space. default: 0.0");
STRIDE.addParameter("min_valid_path_fraction", "0.2", "Accept partially valid moves above fraction. default: 0.2");
planner_des.push_back(STRIDE);
OMPLPlannerDescription BiTRRT("BiTRRT", "geometric");
BiTRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
BiTRRT.addParameter("temp_change_factor", "0.1", "how much to increase or decrease temp. default: 0.1");
BiTRRT.addParameter("init_temperature", "100", "initial temperature. default: 100");
BiTRRT.addParameter("frountier_threshold", "0.0", "dist new state to nearest neighbor to disqualify as frontier. "
"default: 0.0 set in setup()");
BiTRRT.addParameter("frountier_node_ratio", "0.1", "1/10, or 1 nonfrontier for every 10 frontier. default: 0.1");
BiTRRT.addParameter("cost_threshold", "1e300", "the cost threshold. Any motion cost that is not better will not be "
"expanded. default: inf");
planner_des.push_back(BiTRRT);
OMPLPlannerDescription LBTRRT("LBTRRT", "geometric");
LBTRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
LBTRRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
LBTRRT.addParameter("epsilon", "0.4", "optimality approximation factor. default: 0.4");
planner_des.push_back(LBTRRT);
OMPLPlannerDescription BiEST("BiEST", "geometric");
BiEST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
planner_des.push_back(BiEST);
OMPLPlannerDescription ProjEST("ProjEST", "geometric");
ProjEST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
ProjEST.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
planner_des.push_back(ProjEST);
OMPLPlannerDescription LazyPRM("LazyPRM", "geometric");
LazyPRM.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
"setup()");
planner_des.push_back(LazyPRM);
OMPLPlannerDescription LazyPRMstar("LazyPRMstar", "geometric"); // no declares in code
planner_des.push_back(LazyPRMstar);
OMPLPlannerDescription SPARS("SPARS", "geometric");
SPARS.addParameter("stretch_factor", "3.0", "roadmap spanner stretch factor. multiplicative upper bound on path "
"quality. It does not make sense to make this parameter more than 3. "
"default: 3.0");
SPARS.addParameter("sparse_delta_fraction", "0.25", "delta fraction for connection distance. This value represents "
"the visibility range of sparse samples. default: 0.25");
SPARS.addParameter("dense_delta_fraction", "0.001", "delta fraction for interface detection. default: 0.001");
SPARS.addParameter("max_failures", "1000", "maximum consecutive failure limit. default: 1000");
planner_des.push_back(SPARS);
OMPLPlannerDescription SPARStwo("SPARStwo", "geometric");
SPARStwo.addParameter("stretch_factor", "3.0", "roadmap spanner stretch factor. multiplicative upper bound on path "
"quality. It does not make sense to make this parameter more than 3. "
"default: 3.0");
SPARStwo.addParameter("sparse_delta_fraction", "0.25",
"delta fraction for connection distance. This value represents "
"the visibility range of sparse samples. default: 0.25");
SPARStwo.addParameter("dense_delta_fraction", "0.001", "delta fraction for interface detection. default: 0.001");
SPARStwo.addParameter("max_failures", "5000", "maximum consecutive failure limit. default: 5000");
planner_des.push_back(SPARStwo);
return planner_des;
}
// ******************************************************************************************
// Helper function to write the FollowJointTrajectory for each planning group to ros_controller.yaml,
// and erases the controller that have been written, to avoid mixing between FollowJointTrajectory
// which are published under the namespace of 'controller_list' and other types of controllers.
// ******************************************************************************************
void MoveItConfigData::outputFollowJointTrajectoryYAML(YAML::Emitter& emitter,
std::vector<ROSControlConfig>& ros_controllers_config_output)
{
// Write default controllers
emitter << YAML::Key << "controller_list";
emitter << YAML::Value << YAML::BeginSeq;
{
for (std::vector<ROSControlConfig>::iterator controller_it = ros_controllers_config_output.begin();
controller_it != ros_controllers_config_output.end();)
{
// Depending on the controller type, fill the required data
if (controller_it->type_ == "FollowJointTrajectory")
{
emitter << YAML::BeginMap;
emitter << YAML::Key << "name";
emitter << YAML::Value << controller_it->name_;
emitter << YAML::Key << "action_ns";
emitter << YAML::Value << "follow_joint_trajectory";
emitter << YAML::Key << "default";
emitter << YAML::Value << "True";
emitter << YAML::Key << "type";
emitter << YAML::Value << controller_it->type_;
// Write joints
emitter << YAML::Key << "joints";
{
if (controller_it->joints_.size() != 1)
{
emitter << YAML::Value << YAML::BeginSeq;
// Iterate through the joints
for (std::vector<std::string>::iterator joint_it = controller_it->joints_.begin();
joint_it != controller_it->joints_.end(); ++joint_it)
{
emitter << *joint_it;
}
emitter << YAML::EndSeq;
}
else
{
emitter << YAML::Value << YAML::BeginMap;
emitter << controller_it->joints_[0];
emitter << YAML::EndMap;
}
}
ros_controllers_config_output.erase(controller_it);
emitter << YAML::EndMap;
}
else
{
controller_it++;
}
}
emitter << YAML::EndSeq;
}
}
// ******************************************************************************************
// Output controllers config files
// ******************************************************************************************
bool MoveItConfigData::outputROSControllersYAML(const std::string& file_path)
{
// Copy ros_control_config_ to a new vector to avoid modifying it
std::vector<ROSControlConfig> ros_controllers_config_output(ros_controllers_config_);
// Cache the joints' names.
std::vector<std::vector<std::string>> planning_groups;
std::vector<std::string> group_joints;
// We are going to write the joints names many times.
// Loop through groups to store the joints names in group_joints vector and reuse is.
for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
++group_it)
{
// Get list of associated joints
const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
// Iterate through the joints and push into group_joints vector.
for (const robot_model::JointModel* joint : joint_models)
{
if (joint->isPassive() || joint->getMimic() != NULL || joint->getType() == robot_model::JointModel::FIXED)
continue;
else
group_joints.push_back(joint->getName());
}
// Push all the group joints into planning_groups vector.
planning_groups.push_back(group_joints);
group_joints.clear();
}
YAML::Emitter emitter;
emitter << YAML::BeginMap;
// Start with the robot name ---------------------------------------------------
emitter << YAML::Key << srdf_->srdf_model_->getName();
emitter << YAML::Value << YAML::BeginMap;
{
emitter << YAML::Comment("MoveIt-specific simulation settings");
emitter << YAML::Key << "moveit_sim_hw_interface" << YAML::Value << YAML::BeginMap;
// Moveit Simulation Controller settings for setting initial pose
{
emitter << YAML::Key << "joint_model_group";
emitter << YAML::Value << "controllers_initial_group_";
emitter << YAML::Key << "joint_model_group_pose";
emitter << YAML::Value << "controllers_initial_pose_";
emitter << YAML::EndMap;
}
// Settings for ros_control control loop
emitter << YAML::Newline;
emitter << YAML::Comment("Settings for ros_control control loop");
emitter << YAML::Key << "generic_hw_control_loop" << YAML::Value << YAML::BeginMap;
{
emitter << YAML::Key << "loop_hz";
emitter << YAML::Value << "300";
emitter << YAML::Key << "cycle_time_error_threshold";
emitter << YAML::Value << "0.01";
emitter << YAML::EndMap;
}
// Settings for ros_control hardware interface
emitter << YAML::Newline;
emitter << YAML::Comment("Settings for ros_control hardware interface");
emitter << YAML::Key << "hardware_interface" << YAML::Value << YAML::BeginMap;
{
// Get list of all joints for the robot
const std::vector<const robot_model::JointModel*>& joint_models = getRobotModel()->getJointModels();
emitter << YAML::Key << "joints";
{
if (joint_models.size() != 1)
{
emitter << YAML::Value << YAML::BeginSeq;
// Iterate through the joints
for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
joint_it < joint_models.end(); ++joint_it)
{
if ((*joint_it)->isPassive() || (*joint_it)->getMimic() != NULL ||
(*joint_it)->getType() == robot_model::JointModel::FIXED)
continue;
else
emitter << (*joint_it)->getName();
}
emitter << YAML::EndSeq;
}
else
{
emitter << YAML::Value << YAML::BeginMap;
emitter << joint_models[0]->getName();
emitter << YAML::EndMap;
}
}
emitter << YAML::Key << "sim_control_mode";
emitter << YAML::Value << "1";
emitter << YAML::Comment("0: position, 1: velocity");
emitter << YAML::Newline;
emitter << YAML::EndMap;
}
// Joint State Controller
emitter << YAML::Comment("Publish all joint states");
emitter << YAML::Newline << YAML::Comment("Creates the /joint_states topic necessary in ROS");
emitter << YAML::Key << "joint_state_controller" << YAML::Value << YAML::BeginMap;
{
emitter << YAML::Key << "type";
emitter << YAML::Value << "joint_state_controller/JointStateController";
emitter << YAML::Key << "publish_rate";
emitter << YAML::Value << "50";
emitter << YAML::EndMap;
}
// Writes Follow Joint Trajectory ROS controllers to ros_controller.yaml
outputFollowJointTrajectoryYAML(emitter, ros_controllers_config_output);
for (std::vector<ROSControlConfig>::const_iterator controller_it = ros_controllers_config_output.begin();
controller_it != ros_controllers_config_output.end(); ++controller_it)
{
emitter << YAML::Key << controller_it->name_;
emitter << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "type";
emitter << YAML::Value << controller_it->type_;
// Write joints
emitter << YAML::Key << "joints";
{
if (controller_it->joints_.size() != 1)
{
emitter << YAML::Value << YAML::BeginSeq;
// Iterate through the joints
for (std::vector<std::string>::const_iterator joint_it = controller_it->joints_.begin();
joint_it != controller_it->joints_.end(); ++joint_it)
{
emitter << *joint_it;
}
emitter << YAML::EndSeq;
}
else
{
emitter << YAML::Value << YAML::BeginMap;
emitter << controller_it->joints_[0];
emitter << YAML::EndMap;
}
}
// Write gains as they are required for vel and effort controllers
emitter << YAML::Key << "gains";
emitter << YAML::Value << YAML::BeginMap;
{
// Iterate through the joints
for (std::vector<std::string>::const_iterator joint_it = controller_it->joints_.begin();
joint_it != controller_it->joints_.end(); ++joint_it)
{
emitter << YAML::Key << *joint_it << YAML::Value << YAML::BeginMap;
emitter << YAML::Key << "p";
emitter << YAML::Value << "100";
emitter << YAML::Key << "d";
emitter << YAML::Value << "1";
emitter << YAML::Key << "i";
emitter << YAML::Value << "1";
emitter << YAML::Key << "i_clamp";
emitter << YAML::Value << "1" << YAML::EndMap;
}
emitter << YAML::EndMap;
}
emitter << YAML::EndMap;
}
}
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Output 3D Sensor configuration file
// ******************************************************************************************
bool MoveItConfigData::output3DSensorPluginYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
emitter << YAML::Comment("The name of this file shouldn't be changed, or else the Setup Assistant won't detect it");
emitter << YAML::Key << "sensors";
emitter << YAML::Value << YAML::BeginSeq;
// Can we have more than one plugin config?
emitter << YAML::BeginMap;
// Make sure sensors_plugin_config_parameter_list_ is not empty
if (!sensors_plugin_config_parameter_list_.empty())
{
for (auto& parameter : sensors_plugin_config_parameter_list_[0])
{
emitter << YAML::Key << parameter.first;
emitter << YAML::Value << parameter.second.getValue();
}
}
emitter << YAML::EndMap;
emitter << YAML::EndSeq;
emitter << YAML::EndMap;
std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
if (!output_stream.good())
{
ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
return false;
}
output_stream << emitter.c_str();
output_stream.close();
return true; // file created successfully
}
// ******************************************************************************************
// Output joint limits config files
// ******************************************************************************************
bool MoveItConfigData::outputJointLimitsYAML(const std::string& file_path)
{
YAML::Emitter emitter;
emitter << YAML::BeginMap;
emitter << YAML::Key << "joint_limits";
emitter << YAML::Value << YAML::BeginMap;
// Union all the joints in groups. Uses a custom comparator to allow the joints to be sorted by name
std::set<const robot_model::JointModel*, joint_model_compare> joints;
// Loop through groups
for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
++group_it)
{
// Get list of associated joints
const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getJointModels();
// Iterate through the joints
for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
joint_it != joint_models.end(); ++joint_it)
{
// Check that this joint only represents 1 variable.
if ((*joint_it)->getVariableCount() == 1)
joints.insert(*joint_it);
}
}
// Add joints to yaml file, if no more than 1 dof
for (std::set<const robot_model::JointModel*>::iterator joint_it = joints.begin(); joint_it != joints.end();
++joint_it)
{
emitter << YAML::Key << (*joint_it)->getName();
emitter << YAML::Value << YAML::BeginMap;
const robot_model::VariableBounds& b = (*joint_it)->getVariableBounds()[0];
// Output property
emitter << YAML::Key << "has_velocity_limits";
if (b.velocity_bounded_)
emitter << YAML::Value << "true";
else
emitter << YAML::Value << "false";