-
Notifications
You must be signed in to change notification settings - Fork 531
/
slam_toolbox_common.cpp
1109 lines (980 loc) · 39.1 KB
/
slam_toolbox_common.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
/*
* slam_toolbox
* Copyright Work Modifications (c) 2018, Simbe Robotics, Inc.
* Copyright Work Modifications (c) 2019, Samsung Research America
*
* THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
* COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
* COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
* AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
*
* BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
* BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
* CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
* CONDITIONS.
*
*/
/* Author: Steven Macenski */
#include <memory>
#include <vector>
#include <string>
#include <chrono>
#include "slam_toolbox/slam_toolbox_common.hpp"
#include "rclcpp/rclcpp/qos.hpp"
#include "slam_toolbox/serialization.hpp"
namespace slam_toolbox
{
/*****************************************************************************/
SlamToolbox::SlamToolbox()
: SlamToolbox(rclcpp::NodeOptions())
/*****************************************************************************/
{
}
/*****************************************************************************/
SlamToolbox::SlamToolbox(rclcpp::NodeOptions options)
: rclcpp_lifecycle::LifecycleNode("slam_toolbox", "", options),
solver_loader_("slam_toolbox", "karto::ScanSolver"),
processor_type_(PROCESS),
first_measurement_(true),
process_near_pose_(nullptr),
transform_timeout_(rclcpp::Duration::from_seconds(0.5)),
minimum_time_interval_(std::chrono::nanoseconds(0))
/*****************************************************************************/
{
int stack_size = 40'000'000;
{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.read_only = true;
this->declare_parameter(
"stack_size_to_use", rclcpp::ParameterType::PARAMETER_INTEGER, descriptor);
if (this->get_parameter("stack_size_to_use", stack_size)) {
RCLCPP_INFO(get_logger(), "Node using stack size %i", (int)stack_size);
const rlim_t max_stack_size = stack_size;
struct rlimit stack_limit;
getrlimit(RLIMIT_STACK, &stack_limit);
if (stack_limit.rlim_cur < stack_size) {
stack_limit.rlim_cur = stack_size;
}
setrlimit(RLIMIT_STACK, &stack_limit);
}
}
// server side never times out from lifecycle manager
this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true);
this->set_parameter(
rclcpp::Parameter(
bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true));
}
/*****************************************************************************/
void SlamToolbox::createBond()
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
bond_ = std::make_unique<bond::Bond>(
std::string("bond"),
this->get_name(),
shared_from_this());
bond_->setHeartbeatPeriod(0.10);
bond_->setHeartbeatTimeout(4.0);
bond_->start();
}
/*****************************************************************************/
void SlamToolbox::destroyBond()
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());
if (bond_) {
bond_.reset();
}
}
/*****************************************************************************/
CallbackReturn SlamToolbox::on_configure(const rclcpp_lifecycle::State &)
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Configuring");
processor_type_ = PROCESS;
first_measurement_ = true;
process_near_pose_ = nullptr;
smapper_ = std::make_unique<mapper_utils::SMapper>();
dataset_ = std::make_unique<Dataset>();
setParams();
setSolver();
double tmp_val = 30.0;
if (!this->has_parameter("tf_buffer_duration")) {
this->declare_parameter("tf_buffer_duration", tmp_val);
}
tmp_val = this->get_parameter("tf_buffer_duration").as_double();
tf_ = std::make_unique<tf2_ros::Buffer>(this->get_clock(),
tf2::durationFromSec(tmp_val));
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
get_node_base_interface(),
get_node_timers_interface());
tf_->setCreateTimerInterface(timer_interface);
tfL_ = std::make_unique<tf2_ros::TransformListener>(*tf_);
tfB_ = std::make_unique<tf2_ros::TransformBroadcaster>(shared_from_this());
laser_assistant_ = std::make_unique<laser_utils::LaserAssistant>(
shared_from_this(), tf_.get(), base_frame_);
pose_helper_ = std::make_unique<pose_utils::GetPoseHelper>(
tf_.get(), base_frame_, odom_frame_);
scan_holder_ = std::make_unique<laser_utils::ScanHolder>(lasers_);
if (use_map_saver_) {
map_saver_ = std::make_unique<map_saver::MapSaver>(shared_from_this(),
map_name_);
}
closure_assistant_ =
std::make_unique<loop_closure_assistant::LoopClosureAssistant>(
shared_from_this(), smapper_->getMapper(), scan_holder_.get(),
state_, processor_type_);
loadPoseGraphByParams();
return CallbackReturn::SUCCESS;
}
/*****************************************************************************/
CallbackReturn SlamToolbox::on_activate(const rclcpp_lifecycle::State &)
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Activating");
setROSInterfaces();
sst_->on_activate();
sstm_->on_activate();
pose_pub_->on_activate();
reprocessing_transform_.setIdentity();
double transform_publish_period = 0.05;
if (!this->has_parameter("transform_publish_period")) {
this->declare_parameter("transform_publish_period", transform_publish_period);
}
transform_publish_period = this->get_parameter("transform_publish_period").as_double();
threads_.push_back(std::make_unique<boost::thread>(
boost::bind(&SlamToolbox::publishTransformLoop,
this, transform_publish_period)));
threads_.push_back(std::make_unique<boost::thread>(
boost::bind(&SlamToolbox::publishVisualizations, this)));
if (use_lifecycle_manager_) {
// create bond connection
createBond();
}
return CallbackReturn::SUCCESS;
}
/*****************************************************************************/
CallbackReturn SlamToolbox::on_deactivate(const rclcpp_lifecycle::State &)
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Deactivating");
for (int i = 0; i != threads_.size(); i++) {
threads_[i]->interrupt();
threads_[i]->join();
threads_[i].reset();
}
threads_.clear();
sst_->on_deactivate();
sstm_->on_deactivate();
pose_pub_->on_deactivate();
// reset interfaces
scan_filter_.reset();
scan_filter_sub_.reset();
ssDesserialize_.reset();
ssSerialize_.reset();
ssPauseMeasurements_.reset();
ssMap_.reset();
sstm_.reset();
sst_.reset();
pose_pub_.reset();
ssReset_.reset();
if (use_lifecycle_manager_) {
// destroy bond connection
destroyBond();
}
return CallbackReturn::SUCCESS;
}
/*****************************************************************************/
CallbackReturn SlamToolbox::on_cleanup(const rclcpp_lifecycle::State &)
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Cleaning up");
closure_assistant_.reset();
smapper_.reset();
dataset_.reset();
map_saver_.reset();
pose_helper_.reset();
laser_assistant_.reset();
scan_holder_.reset();
solver_.reset();
tfB_.reset();
tfL_.reset();
tf_.reset();
lasers_.clear();
return CallbackReturn::SUCCESS;
}
/*****************************************************************************/
CallbackReturn
SlamToolbox::on_shutdown(const rclcpp_lifecycle::State & state)
/*****************************************************************************/
{
RCLCPP_INFO(get_logger(), "Shutting down");
return CallbackReturn::SUCCESS;
}
/*****************************************************************************/
SlamToolbox::~SlamToolbox()
/*****************************************************************************/
{
for (int i = 0; i != threads_.size(); i++) {
threads_[i]->interrupt();
threads_[i]->join();
threads_[i].reset();
}
threads_.clear();
smapper_.reset();
dataset_.reset();
closure_assistant_.reset();
map_saver_.reset();
pose_helper_.reset();
laser_assistant_.reset();
scan_holder_.reset();
solver_.reset();
scan_filter_.reset();
scan_filter_sub_.reset();
ssDesserialize_.reset();
ssSerialize_.reset();
ssPauseMeasurements_.reset();
ssMap_.reset();
sstm_.reset();
sst_.reset();
pose_pub_.reset();
ssReset_.reset();
tfB_.reset();
tfL_.reset();
tf_.reset();
lasers_.clear();
}
/*****************************************************************************/
void SlamToolbox::setSolver()
/*****************************************************************************/
{
// Set solver to be used in loop closure
std::string solver_plugin = std::string("solver_plugins::CeresSolver");
if (!this->has_parameter("solver_plugin")) {
this->declare_parameter("solver_plugin", solver_plugin);
}
solver_plugin = this->get_parameter("solver_plugin").as_string();
try {
solver_ = solver_loader_.createSharedInstance(solver_plugin);
RCLCPP_INFO(get_logger(), "Using solver plugin %s",
solver_plugin.c_str());
solver_->Configure(shared_from_this());
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(get_logger(), "Failed to create %s, is it "
"registered and built? Exception: %s.", solver_plugin.c_str(), ex.what());
exit(1);
}
smapper_->getMapper()->SetScanSolver(solver_.get());
}
/*****************************************************************************/
void SlamToolbox::setParams()
/*****************************************************************************/
{
map_to_odom_.setIdentity();
odom_frame_ = std::string("odom");
if (!this->has_parameter("odom_frame")) {
this->declare_parameter("odom_frame", odom_frame_);
}
odom_frame_ = this->get_parameter("odom_frame").as_string();
map_frame_ = std::string("map");
if (!this->has_parameter("map_frame")) {
this->declare_parameter("map_frame", map_frame_);
}
map_frame_ = this->get_parameter("map_frame").as_string();
base_frame_ = std::string("base_footprint");
if (!this->has_parameter("base_frame")) {
this->declare_parameter("base_frame", base_frame_);
}
base_frame_ = this->get_parameter("base_frame").as_string();
resolution_ = 0.05;
if (!this->has_parameter("resolution")) {
this->declare_parameter("resolution", resolution_);
}
resolution_ = this->get_parameter("resolution").as_double();
if (resolution_ <= 0.0) {
RCLCPP_WARN(this->get_logger(),
"You've set resolution of map to be zero or negative,"
"this isn't allowed so it will be set to default value 0.05.");
resolution_ = 0.05;
}
map_name_ = std::string("/map");
if (!this->has_parameter("map_name")) {
this->declare_parameter("map_name", map_name_);
}
map_name_ = this->get_parameter("map_name").as_string();
use_map_saver_ = true;
if (!this->has_parameter("use_map_saver")) {
this->declare_parameter("use_map_saver", use_map_saver_);
}
use_map_saver_ = this->get_parameter("use_map_saver").as_bool();
use_lifecycle_manager_ = false;
if (!this->has_parameter("use_lifecycle_manager")) {
this->declare_parameter("use_lifecycle_manager", use_lifecycle_manager_);
}
use_lifecycle_manager_ = this->get_parameter("use_lifecycle_manager").as_bool();
scan_topic_ = std::string("/scan");
if (!this->has_parameter("scan_topic")) {
this->declare_parameter("scan_topic", scan_topic_);
}
scan_topic_ = this->get_parameter("scan_topic").as_string();
scan_queue_size_ = 1;
if (!this->has_parameter("scan_queue_size")) {
this->declare_parameter("scan_queue_size", scan_queue_size_);
}
scan_queue_size_ = this->get_parameter("scan_queue_size").as_int();
throttle_scans_ = 1;
if (!this->has_parameter("throttle_scans")) {
this->declare_parameter("throttle_scans", throttle_scans_);
}
throttle_scans_ = this->get_parameter("throttle_scans").as_int();
if (throttle_scans_ == 0) {
RCLCPP_WARN(this->get_logger(),
"You've set throttle_scans to be zero,"
"this isn't allowed so it will be set to default value 1.");
throttle_scans_ = 1;
}
position_covariance_scale_ = 1.0;
if (!this->has_parameter("position_covariance_scale")) {
this->declare_parameter("position_covariance_scale", position_covariance_scale_);
}
position_covariance_scale_ = this->get_parameter("position_covariance_scale").as_double();
yaw_covariance_scale_ = 1.0;
if (!this->has_parameter("yaw_covariance_scale")) {
this->declare_parameter("yaw_covariance_scale", yaw_covariance_scale_);
}
yaw_covariance_scale_ = this->get_parameter("yaw_covariance_scale").as_double();
enable_interactive_mode_ = false;
if (!this->has_parameter("enable_interactive_mode")) {
this->declare_parameter("enable_interactive_mode", enable_interactive_mode_);
}
enable_interactive_mode_ = this->get_parameter("enable_interactive_mode").as_bool();
double tmp_val = 0.5;
if (!this->has_parameter("transform_timeout")) {
this->declare_parameter("transform_timeout", tmp_val);
}
tmp_val = this->get_parameter("transform_timeout").as_double();
transform_timeout_ = rclcpp::Duration::from_seconds(tmp_val);
if (!this->has_parameter("minimum_time_interval")) {
this->declare_parameter("minimum_time_interval", tmp_val);
}
tmp_val = this->get_parameter("minimum_time_interval").as_double();
minimum_time_interval_ = rclcpp::Duration::from_seconds(tmp_val);
bool debug = false;
if (!this->has_parameter("debug_logging")) {
this->declare_parameter("debug_logging", debug);
}
debug = this->get_parameter("debug_logging").as_bool();
if (debug) {
rcutils_ret_t rtn = rcutils_logging_set_logger_level("logger_name",
RCUTILS_LOG_SEVERITY_DEBUG);
}
smapper_->configure(shared_from_this());
if (!this->has_parameter("paused_new_measurements")) {
this->declare_parameter("paused_new_measurements", false);
}
this->set_parameter(rclcpp::Parameter("paused_new_measurements", false));
}
/*****************************************************************************/
void SlamToolbox::setROSInterfaces()
/*****************************************************************************/
{
pose_pub_ = this->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"pose", 10);
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
map_name_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>(
map_name_ + "_metadata",
rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
ssMap_ = this->create_service<nav_msgs::srv::GetMap>("slam_toolbox/dynamic_map",
std::bind(&SlamToolbox::mapCallback, this, std::placeholders::_1,
std::placeholders::_2, std::placeholders::_3));
ssPauseMeasurements_ = this->create_service<slam_toolbox::srv::Pause>(
"slam_toolbox/pause_new_measurements",
std::bind(&SlamToolbox::pauseNewMeasurementsCallback,
this, std::placeholders::_1,
std::placeholders::_2, std::placeholders::_3));
ssSerialize_ = this->create_service<slam_toolbox::srv::SerializePoseGraph>(
"slam_toolbox/serialize_map",
std::bind(&SlamToolbox::serializePoseGraphCallback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
ssDesserialize_ = this->create_service<slam_toolbox::srv::DeserializePoseGraph>(
"slam_toolbox/deserialize_map",
std::bind(&SlamToolbox::deserializePoseGraphCallback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
ssReset_ = this->create_service<slam_toolbox::srv::Reset>(
"slam_toolbox/reset",
std::bind(&SlamToolbox::resetCallback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
scan_filter_sub_ =
std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
shared_from_this().get(), scan_topic_, rclcpp::SensorDataQoS());
scan_filter_ =
std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*scan_filter_sub_, *tf_, odom_frame_, scan_queue_size_,
get_node_logging_interface(), get_node_clock_interface(),
tf2::durationFromSec(transform_timeout_.seconds()));
scan_filter_->registerCallback(
std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));
}
/*****************************************************************************/
void SlamToolbox::publishTransformLoop(
const double & transform_publish_period)
/*****************************************************************************/
{
if (transform_publish_period == 0) {
return;
}
rclcpp::Rate r(1.0 / transform_publish_period);
while (rclcpp::ok()) {
boost::this_thread::interruption_point();
{
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
rclcpp::Time scan_timestamp = scan_header.stamp;
// Avoid publishing tf with initial 0.0 scan timestamp
if (scan_timestamp.seconds() > 0.0 && !scan_header.frame_id.empty()) {
geometry_msgs::msg::TransformStamped msg;
msg.transform = tf2::toMsg(map_to_odom_);
msg.child_frame_id = odom_frame_;
msg.header.frame_id = map_frame_;
msg.header.stamp = scan_timestamp + transform_timeout_;
tfB_->sendTransform(msg);
}
}
r.sleep();
}
}
/*****************************************************************************/
void SlamToolbox::publishVisualizations()
/*****************************************************************************/
{
nav_msgs::msg::OccupancyGrid & og = map_.map;
og.info.resolution = resolution_;
og.info.origin.position.x = 0.0;
og.info.origin.position.y = 0.0;
og.info.origin.position.z = 0.0;
og.info.origin.orientation.x = 0.0;
og.info.origin.orientation.y = 0.0;
og.info.origin.orientation.z = 0.0;
og.info.origin.orientation.w = 1.0;
og.header.frame_id = map_frame_;
double map_update_interval = 10.0;
if (!this->has_parameter("map_update_interval")) {
this->declare_parameter("map_update_interval", map_update_interval);
}
map_update_interval = this->get_parameter("map_update_interval").as_double();
rclcpp::Rate r(1.0 / map_update_interval);
while (rclcpp::ok()) {
boost::this_thread::interruption_point();
updateMap();
if (!isPaused(VISUALIZING_GRAPH)) {
boost::mutex::scoped_lock lock(smapper_mutex_);
closure_assistant_->publishGraph();
}
r.sleep();
}
}
/*****************************************************************************/
void SlamToolbox::loadPoseGraphByParams()
/*****************************************************************************/
{
std::string filename;
geometry_msgs::msg::Pose2D pose;
bool dock = false;
if (shouldStartWithPoseGraph(filename, pose, dock)) {
std::shared_ptr<slam_toolbox::srv::DeserializePoseGraph::Request> req =
std::make_shared<slam_toolbox::srv::DeserializePoseGraph::Request>();
std::shared_ptr<slam_toolbox::srv::DeserializePoseGraph::Response> resp =
std::make_shared<slam_toolbox::srv::DeserializePoseGraph::Response>();
req->initial_pose = pose;
req->filename = filename;
if (dock) {
req->match_type =
slam_toolbox::srv::DeserializePoseGraph::Request::START_AT_FIRST_NODE;
} else {
req->match_type =
slam_toolbox::srv::DeserializePoseGraph::Request::START_AT_GIVEN_POSE;
}
deserializePoseGraphCallback(nullptr, req, resp);
}
}
/*****************************************************************************/
bool SlamToolbox::shouldStartWithPoseGraph(
std::string & filename,
geometry_msgs::msg::Pose2D & pose, bool & start_at_dock)
/*****************************************************************************/
{
// if given a map to load at run time, do it.
if (!this->has_parameter("map_start_pose")) {
this->declare_parameter("map_start_pose", std::vector<double>());
}
auto map_start_pose = this->get_parameter("map_start_pose").get_parameter_value();
if (!this->has_parameter("map_start_at_dock")) {
this->declare_parameter("map_start_at_dock", false);
}
auto map_start_at_dock = this->get_parameter("map_start_at_dock").get_parameter_value();
if (!this->has_parameter("map_file_name")) {
this->declare_parameter("map_file_name", std::string(""));
}
filename = this->get_parameter("map_file_name").as_string();
if (!filename.empty()) {
std::vector<double> read_pose;
if (map_start_pose.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) {
read_pose = map_start_pose.get<std::vector<double>>();
start_at_dock = false;
if (read_pose.size() != 3) {
RCLCPP_ERROR(get_logger(), "LocalizationSlamToolbox: Incorrect "
"number of arguments for map starting pose. Must be in format: "
"[x, y, theta]. Starting at the origin");
pose.x = 0.;
pose.y = 0.;
pose.theta = 0.;
} else {
pose.x = read_pose[0];
pose.y = read_pose[1];
pose.theta = read_pose[2];
}
} else if (map_start_at_dock.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) {
start_at_dock = map_start_at_dock.get<bool>();
} else {
RCLCPP_ERROR(get_logger(), "LocalizationSlamToolbox: Map starting "
"pose not specified. Set either map_start_pose or map_start_at_dock.");
return false;
}
return true;
}
return false;
}
/*****************************************************************************/
LaserRangeFinder * SlamToolbox::getLaser(
const
sensor_msgs::msg::LaserScan::ConstSharedPtr & scan)
/*****************************************************************************/
{
const std::string & frame = scan->header.frame_id;
if (lasers_.find(frame) == lasers_.end()) {
try {
lasers_[frame] = laser_assistant_->toLaserMetadata(*scan);
dataset_->Add(lasers_[frame].getLaser(), true);
} catch (tf2::TransformException & e) {
RCLCPP_ERROR(get_logger(), "Failed to compute laser pose, "
"aborting initialization (%s)", e.what());
return nullptr;
}
}
return lasers_[frame].getLaser();
}
/*****************************************************************************/
bool SlamToolbox::updateMap()
/*****************************************************************************/
{
if (!sst_ || !sst_->is_activated() || sst_->get_subscription_count() == 0) {
return true;
}
boost::mutex::scoped_lock lock(smapper_mutex_);
OccupancyGrid * occ_grid = smapper_->getOccupancyGrid(resolution_);
if (!occ_grid) {
return false;
}
vis_utils::toNavMap(occ_grid, map_.map);
// publish map as current
map_.map.header.stamp = scan_header.stamp;
sst_->publish(
std::move(std::make_unique<nav_msgs::msg::OccupancyGrid>(map_.map)));
sstm_->publish(
std::move(std::make_unique<nav_msgs::msg::MapMetaData>(map_.map.info)));
delete occ_grid;
occ_grid = nullptr;
return true;
}
/*****************************************************************************/
tf2::Stamped<tf2::Transform> SlamToolbox::setTransformFromPoses(
const Pose2 & corrected_pose,
const Pose2 & odom_pose,
const rclcpp::Time & t,
const bool & update_reprocessing_transform)
/*****************************************************************************/
{
// Compute the map->odom transform
tf2::Stamped<tf2::Transform> odom_to_map;
tf2::Quaternion q(0., 0., 0., 1.0);
q.setRPY(0., 0., corrected_pose.GetHeading());
tf2::Stamped<tf2::Transform> base_to_map(
tf2::Transform(q, tf2::Vector3(corrected_pose.GetX(),
corrected_pose.GetY(), 0.0)).inverse(), tf2_ros::fromMsg(t), base_frame_);
try {
geometry_msgs::msg::TransformStamped base_to_map_msg, odom_to_map_msg;
// https://github.com/ros2/geometry2/issues/176
// not working for some reason...
// base_to_map_msg = tf2::toMsg(base_to_map);
base_to_map_msg.header.stamp = tf2_ros::toMsg(base_to_map.stamp_);
base_to_map_msg.header.frame_id = base_to_map.frame_id_;
base_to_map_msg.transform.translation.x = base_to_map.getOrigin().getX();
base_to_map_msg.transform.translation.y = base_to_map.getOrigin().getY();
base_to_map_msg.transform.translation.z = base_to_map.getOrigin().getZ();
base_to_map_msg.transform.rotation = tf2::toMsg(base_to_map.getRotation());
odom_to_map_msg = tf_->transform(base_to_map_msg, odom_frame_);
tf2::fromMsg(odom_to_map_msg, odom_to_map);
} catch (tf2::TransformException & e) {
RCLCPP_ERROR(get_logger(), "Transform from base_link to odom failed: %s",
e.what());
return odom_to_map;
}
// if we're continuing a previous session, we need to
// estimate the homogenous transformation between the old and new
// odometry frames and transform the new session
// into the older session's frame
if (update_reprocessing_transform) {
tf2::Transform odom_to_base_serialized = base_to_map.inverse();
tf2::Quaternion q1(0., 0., 0., 1.0);
q1.setRPY(0., 0., tf2::getYaw(odom_to_base_serialized.getRotation()));
odom_to_base_serialized.setRotation(q1);
tf2::Transform odom_to_base_current = smapper_->toTfPose(odom_pose);
reprocessing_transform_ =
odom_to_base_serialized * odom_to_base_current.inverse();
}
// set map to odom for our transformation thread to publish
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
map_to_odom_ = tf2::Transform(tf2::Quaternion(odom_to_map.getRotation() ),
tf2::Vector3(odom_to_map.getOrigin() ) ).inverse();
return odom_to_map;
}
/*****************************************************************************/
LocalizedRangeScan * SlamToolbox::getLocalizedRangeScan(
LaserRangeFinder * laser,
const sensor_msgs::msg::LaserScan::ConstSharedPtr & scan,
Pose2 & odom_pose)
/*****************************************************************************/
{
// Create a vector of doubles for lib
std::vector<kt_double> readings = laser_utils::scanToReadings(
*scan, lasers_[scan->header.frame_id].isInverted());
// transform by the reprocessing transform
tf2::Transform pose_original = smapper_->toTfPose(odom_pose);
tf2::Transform tf_pose_transformed = reprocessing_transform_ * pose_original;
Pose2 transformed_pose = smapper_->toKartoPose(tf_pose_transformed);
// create localized range scan
LocalizedRangeScan * range_scan = new LocalizedRangeScan(
laser->GetName(), readings);
range_scan->SetOdometricPose(transformed_pose);
range_scan->SetCorrectedPose(transformed_pose);
range_scan->SetTime(rclcpp::Time(scan->header.stamp).nanoseconds()/1.e9);
return range_scan;
}
/*****************************************************************************/
bool SlamToolbox::shouldProcessScan(
const sensor_msgs::msg::LaserScan::ConstSharedPtr & scan,
const Pose2 & pose)
/*****************************************************************************/
{
static Pose2 last_pose;
static rclcpp::Time last_scan_time = rclcpp::Time(0.);
static double min_dist2 =
smapper_->getMapper()->getParamMinimumTravelDistance() *
smapper_->getMapper()->getParamMinimumTravelDistance();
static int scan_ctr = 0;
scan_ctr++;
// we give it a pass on the first measurement to get the ball rolling
if (first_measurement_) {
last_scan_time = scan->header.stamp;
last_pose = pose;
first_measurement_ = false;
return true;
}
// we are in a paused mode, reject incomming information
if (isPaused(NEW_MEASUREMENTS)) {
return false;
}
// throttled out
if ((scan_ctr % throttle_scans_) != 0) {
return false;
}
// not enough time
if (rclcpp::Time(scan->header.stamp) - last_scan_time < minimum_time_interval_) {
return false;
}
// check moved enough, within 10% for correction error
const double dist2 = last_pose.SquaredDistance(pose);
if (dist2 < 0.8 * min_dist2 || scan_ctr < 5) {
return false;
}
last_pose = pose;
last_scan_time = scan->header.stamp;
return true;
}
/*****************************************************************************/
LocalizedRangeScan * SlamToolbox::addScan(
LaserRangeFinder * laser,
PosedScan & scan_w_pose)
/*****************************************************************************/
{
return addScan(laser, scan_w_pose.scan, scan_w_pose.pose);
}
/*****************************************************************************/
LocalizedRangeScan * SlamToolbox::addScan(
LaserRangeFinder * laser,
const sensor_msgs::msg::LaserScan::ConstSharedPtr & scan,
Pose2 & odom_pose)
/*****************************************************************************/
{
// get our localized range scan
LocalizedRangeScan * range_scan = getLocalizedRangeScan(
laser, scan, odom_pose);
// Add the localized range scan to the smapper
boost::mutex::scoped_lock lock(smapper_mutex_);
bool processed = false, update_reprocessing_transform = false;
Matrix3 covariance;
covariance.SetToIdentity();
if (processor_type_ == PROCESS) {
processed = smapper_->getMapper()->Process(range_scan, &covariance);
} else if (processor_type_ == PROCESS_FIRST_NODE) {
processed = smapper_->getMapper()->ProcessAtDock(range_scan, &covariance);
processor_type_ = PROCESS;
update_reprocessing_transform = true;
} else if (processor_type_ == PROCESS_NEAR_REGION) {
boost::mutex::scoped_lock l(pose_mutex_);
if (!process_near_pose_) {
RCLCPP_ERROR(get_logger(), "Process near region called without a "
"valid region request. Ignoring scan.");
return nullptr;
}
range_scan->SetOdometricPose(*process_near_pose_);
range_scan->SetCorrectedPose(range_scan->GetOdometricPose());
process_near_pose_.reset(nullptr);
processed = smapper_->getMapper()->ProcessAgainstNodesNearBy(
range_scan, false, &covariance);
update_reprocessing_transform = true;
processor_type_ = PROCESS;
} else {
RCLCPP_FATAL(get_logger(),
"SlamToolbox: No valid processor type set! Exiting.");
exit(-1);
}
// if successfully processed, create odom to map transformation
// and add our scan to storage
if (processed) {
if (enable_interactive_mode_) {
scan_holder_->addScan(*scan);
}
setTransformFromPoses(range_scan->GetCorrectedPose(), odom_pose,
scan->header.stamp, update_reprocessing_transform);
dataset_->Add(range_scan);
publishPose(range_scan->GetCorrectedPose(), covariance, scan->header.stamp);
} else {
delete range_scan;
range_scan = nullptr;
}
return range_scan;
}
/*****************************************************************************/
void SlamToolbox::publishPose(
const Pose2 & pose,
const Matrix3 & cov,
const rclcpp::Time & t)
/*****************************************************************************/
{
geometry_msgs::msg::PoseWithCovarianceStamped pose_msg;
pose_msg.header.stamp = t;
pose_msg.header.frame_id = map_frame_;
tf2::Quaternion q(0., 0., 0., 1.0);
q.setRPY(0., 0., pose.GetHeading());
tf2::Transform transform(q, tf2::Vector3(pose.GetX(), pose.GetY(), 0.0));
tf2::toMsg(transform, pose_msg.pose.pose);
pose_msg.pose.covariance[0] = cov(0, 0) * position_covariance_scale_; // x
pose_msg.pose.covariance[1] = cov(0, 1) * position_covariance_scale_; // xy
pose_msg.pose.covariance[6] = cov(1, 0) * position_covariance_scale_; // xy
pose_msg.pose.covariance[7] = cov(1, 1) * position_covariance_scale_; // y
pose_msg.pose.covariance[35] = cov(2, 2) * yaw_covariance_scale_; // yaw
pose_pub_->publish(pose_msg);
}
/*****************************************************************************/
bool SlamToolbox::mapCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav_msgs::srv::GetMap::Request> req,
std::shared_ptr<nav_msgs::srv::GetMap::Response> res)
/*****************************************************************************/
{
if (map_.map.info.width && map_.map.info.height) {
boost::mutex::scoped_lock lock(smapper_mutex_);
*res = map_;
return true;
} else {
return false;
}
}
/*****************************************************************************/
bool SlamToolbox::pauseNewMeasurementsCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<slam_toolbox::srv::Pause::Request> req,
std::shared_ptr<slam_toolbox::srv::Pause::Response> resp)
/*****************************************************************************/
{
bool curr_state = isPaused(NEW_MEASUREMENTS);
state_.set(NEW_MEASUREMENTS, !curr_state);
this->set_parameter({"paused_new_measurements", !curr_state});
RCLCPP_INFO(get_logger(), "SlamToolbox: Toggled to %s",
!curr_state ? "pause taking new measurements." :
"actively taking new measurements.");
resp->status = true;
return true;
}
/*****************************************************************************/
bool SlamToolbox::isPaused(const PausedApplication & app)
/*****************************************************************************/
{
return state_.get(app);
}
/*****************************************************************************/
bool SlamToolbox::serializePoseGraphCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<slam_toolbox::srv::SerializePoseGraph::Request> req,
std::shared_ptr<slam_toolbox::srv::SerializePoseGraph::Response> resp)
/*****************************************************************************/
{
std::string filename = req->filename;
// if we're inside the snap, we need to write to commonly accessible space
if (snap_utils::isInSnap()) {
filename = snap_utils::getSnapPath() + std::string("/") + filename;
}
boost::mutex::scoped_lock lock(smapper_mutex_);
if (serialization::write(filename, *smapper_->getMapper(), *dataset_, shared_from_this())) {
resp->result = resp->RESULT_SUCCESS;
} else {
resp->result = resp->RESULT_FAILED_TO_WRITE_FILE;
}
return true;
}
/*****************************************************************************/
void SlamToolbox::loadSerializedPoseGraph(
std::unique_ptr<Mapper> & mapper,
std::unique_ptr<Dataset> & dataset)
/*****************************************************************************/
{
boost::mutex::scoped_lock lock(smapper_mutex_);
solver_->Reset();
// add the nodes and constraints to the optimizer
VerticeMap mapper_vertices = mapper->GetGraph()->GetVertices();
VerticeMap::iterator vertex_map_it = mapper_vertices.begin();
for (vertex_map_it; vertex_map_it != mapper_vertices.end(); ++vertex_map_it) {
ScanMap::iterator vertex_it = vertex_map_it->second.begin();
for (vertex_it; vertex_it != vertex_map_it->second.end(); ++vertex_it) {
if (vertex_it->second != nullptr) {
solver_->AddNode(vertex_it->second);
}
}
}
EdgeVector mapper_edges = mapper->GetGraph()->GetEdges();
EdgeVector::iterator edges_it = mapper_edges.begin();
for (edges_it; edges_it != mapper_edges.end(); ++edges_it) {
if (*edges_it != nullptr) {
solver_->AddConstraint(*edges_it);
}
}
mapper->SetScanSolver(solver_.get());
// move the memory to our working dataset
smapper_->setMapper(mapper.release());
smapper_->configure(shared_from_this());
dataset_.reset(dataset.release());
if (!smapper_->getMapper()) {
RCLCPP_FATAL(get_logger(),
"loadSerializedPoseGraph: Could not properly load "
"a valid mapping object. Did you modify something by hand?");
exit(-1);
}
closure_assistant_->setMapper(smapper_->getMapper());
if (dataset_->GetLasers().size() < 1) {
RCLCPP_FATAL(get_logger(), "loadSerializedPoseGraph: Cannot deserialize "
"dataset with no laser objects.");