-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
amcl_node.cpp
1653 lines (1434 loc) · 54.8 KB
/
amcl_node.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
/*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/
/* Author: Brian Gerkey */
#include "nav2_amcl/amcl_node.hpp"
#include <algorithm>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "message_filters/subscriber.hpp"
#include "nav2_amcl/angleutils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_amcl/pf/pf.hpp"
#include "nav2_util/string_utils.hpp"
#include "nav2_amcl/sensors/laser/laser.hpp"
#include "rclcpp/node_options.hpp"
#include "tf2/convert.h"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/LinearMath/Transform.h"
#include "tf2_ros/buffer.h"
#include "tf2_ros/message_filter.h"
#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/create_timer_ros.h"
#include "nav2_amcl/portable_utils.hpp"
#include "nav2_util/validate_messages.hpp"
using rcl_interfaces::msg::ParameterType;
using namespace std::chrono_literals;
namespace nav2_amcl
{
using nav2_util::geometry_utils::orientationAroundZAxis;
AmclNode::AmclNode(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("amcl", "", options)
{
RCLCPP_INFO(get_logger(), "Creating");
add_parameter(
"alpha1", rclcpp::ParameterValue(0.2),
"This is the alpha1 parameter", "These are additional constraints for alpha1");
add_parameter(
"alpha2", rclcpp::ParameterValue(0.2),
"This is the alpha2 parameter", "These are additional constraints for alpha2");
add_parameter(
"alpha3", rclcpp::ParameterValue(0.2),
"This is the alpha3 parameter", "These are additional constraints for alpha3");
add_parameter(
"alpha4", rclcpp::ParameterValue(0.2),
"This is the alpha4 parameter", "These are additional constraints for alpha4");
add_parameter(
"alpha5", rclcpp::ParameterValue(0.2),
"This is the alpha5 parameter", "These are additional constraints for alpha5");
add_parameter(
"base_frame_id", rclcpp::ParameterValue(std::string("base_footprint")),
"Which frame to use for the robot base");
add_parameter("beam_skip_distance", rclcpp::ParameterValue(0.5));
add_parameter("beam_skip_error_threshold", rclcpp::ParameterValue(0.9));
add_parameter("beam_skip_threshold", rclcpp::ParameterValue(0.3));
add_parameter("do_beamskip", rclcpp::ParameterValue(false));
add_parameter(
"global_frame_id", rclcpp::ParameterValue(std::string("map")),
"The name of the coordinate frame published by the localization system");
add_parameter(
"lambda_short", rclcpp::ParameterValue(0.1),
"Exponential decay parameter for z_short part of model");
add_parameter(
"laser_likelihood_max_dist", rclcpp::ParameterValue(2.0),
"Maximum distance to do obstacle inflation on map, for use in likelihood_field model");
add_parameter(
"laser_max_range", rclcpp::ParameterValue(100.0),
"Maximum scan range to be considered",
"-1.0 will cause the laser's reported maximum range to be used");
add_parameter(
"laser_min_range", rclcpp::ParameterValue(-1.0),
"Minimum scan range to be considered",
"-1.0 will cause the laser's reported minimum range to be used");
add_parameter(
"laser_model_type", rclcpp::ParameterValue(std::string("likelihood_field")),
"Which model to use, either beam, likelihood_field, or likelihood_field_prob",
"Same as likelihood_field but incorporates the beamskip feature, if enabled");
add_parameter(
"set_initial_pose", rclcpp::ParameterValue(false),
"Causes AMCL to set initial pose from the initial_pose* parameters instead of "
"waiting for the initial_pose message");
add_parameter(
"initial_pose.x", rclcpp::ParameterValue(0.0),
"X coordinate of the initial robot pose in the map frame");
add_parameter(
"initial_pose.y", rclcpp::ParameterValue(0.0),
"Y coordinate of the initial robot pose in the map frame");
add_parameter(
"initial_pose.z", rclcpp::ParameterValue(0.0),
"Z coordinate of the initial robot pose in the map frame");
add_parameter(
"initial_pose.yaw", rclcpp::ParameterValue(0.0),
"Yaw of the initial robot pose in the map frame");
add_parameter(
"max_beams", rclcpp::ParameterValue(60),
"How many evenly-spaced beams in each scan to be used when updating the filter");
add_parameter(
"max_particles", rclcpp::ParameterValue(2000),
"Maximum allowed number of particles");
add_parameter(
"min_particles", rclcpp::ParameterValue(500),
"Minimum allowed number of particles");
add_parameter(
"odom_frame_id", rclcpp::ParameterValue(std::string("odom")),
"Which frame to use for odometry");
add_parameter("pf_err", rclcpp::ParameterValue(0.05));
add_parameter("pf_z", rclcpp::ParameterValue(0.99));
add_parameter(
"recovery_alpha_fast", rclcpp::ParameterValue(0.0),
"Exponential decay rate for the fast average weight filter, used in deciding when to recover "
"by adding random poses",
"A good value might be 0.1");
add_parameter(
"recovery_alpha_slow", rclcpp::ParameterValue(0.0),
"Exponential decay rate for the slow average weight filter, used in deciding when to recover "
"by adding random poses",
"A good value might be 0.001");
add_parameter(
"resample_interval", rclcpp::ParameterValue(1),
"Number of filter updates required before resampling");
add_parameter("robot_model_type", rclcpp::ParameterValue("nav2_amcl::DifferentialMotionModel"));
add_parameter(
"save_pose_rate", rclcpp::ParameterValue(0.5),
"Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter "
"server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used "
"on subsequent runs to initialize the filter",
"-1.0 to disable");
add_parameter("sigma_hit", rclcpp::ParameterValue(0.2));
add_parameter(
"tf_broadcast", rclcpp::ParameterValue(true),
"Set this to false to prevent amcl from publishing the transform between the global frame and "
"the odometry frame");
add_parameter(
"transform_tolerance", rclcpp::ParameterValue(1.0),
"Time with which to post-date the transform that is published, to indicate that this transform "
"is valid into the future");
add_parameter(
"update_min_a", rclcpp::ParameterValue(0.2),
"Rotational movement required before performing a filter update");
add_parameter(
"update_min_d", rclcpp::ParameterValue(0.25),
"Translational movement required before performing a filter update");
add_parameter("z_hit", rclcpp::ParameterValue(0.5));
add_parameter("z_max", rclcpp::ParameterValue(0.05));
add_parameter("z_rand", rclcpp::ParameterValue(0.5));
add_parameter("z_short", rclcpp::ParameterValue(0.05));
add_parameter(
"always_reset_initial_pose", rclcpp::ParameterValue(false),
"Requires that AMCL is provided an initial pose either via topic or initial_pose* parameter "
"(with parameter set_initial_pose: true) when reset. Otherwise, by default AMCL will use the"
"last known pose to initialize");
add_parameter(
"scan_topic", rclcpp::ParameterValue("scan"),
"Topic to subscribe to in order to receive the laser scan for localization");
add_parameter(
"map_topic", rclcpp::ParameterValue("map"),
"Topic to subscribe to in order to receive the map to localize on");
add_parameter(
"first_map_only", rclcpp::ParameterValue(false),
"Set this to true, when you want to load a new map published from the map_server");
add_parameter(
"freespace_downsampling", rclcpp::ParameterValue(
false),
"Downsample the free space used by the Pose Generator. Use it with large maps to save memory");
}
AmclNode::~AmclNode()
{
}
nav2_util::CallbackReturn
AmclNode::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Configuring");
callback_group_ = create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive, false);
initParameters();
initTransforms();
initParticleFilter();
initLaserScan();
initMessageFilters();
initPubSub();
initServices();
initOdometry();
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor_->add_callback_group(callback_group_, get_node_base_interface());
executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");
// Lifecycle publishers must be explicitly activated
pose_pub_->on_activate();
particle_cloud_pub_->on_activate();
first_pose_sent_ = false;
// Keep track of whether we're in the active state. We won't
// process incoming callbacks until we are
active_ = true;
if (set_initial_pose_) {
auto msg = std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>();
msg->header.stamp = now();
msg->header.frame_id = global_frame_id_;
msg->pose.pose.position.x = initial_pose_x_;
msg->pose.pose.position.y = initial_pose_y_;
msg->pose.pose.position.z = initial_pose_z_;
msg->pose.pose.orientation = orientationAroundZAxis(initial_pose_yaw_);
initialPoseReceived(msg);
} else if (init_pose_received_on_inactive) {
handleInitialPose(last_published_pose_);
}
auto node = shared_from_this();
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&AmclNode::dynamicParametersCallback,
this, std::placeholders::_1));
// create bond connection
createBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");
active_ = false;
// Lifecycle publishers must be explicitly deactivated
pose_pub_->on_deactivate();
particle_cloud_pub_->on_deactivate();
// shutdown and reset dynamic parameter handler
remove_on_set_parameters_callback(dyn_params_handler_.get());
dyn_params_handler_.reset();
// destroy bond connection
destroyBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
executor_thread_.reset();
// Get rid of the inputs first (services and message filter input), so we
// don't continue to process incoming messages
global_loc_srv_.reset();
initial_guess_srv_.reset();
nomotion_update_srv_.reset();
initial_pose_sub_.reset();
laser_scan_connection_.disconnect();
tf_listener_.reset(); // listener may access lase_scan_filter_, so it should be reset earlier
laser_scan_filter_.reset();
laser_scan_sub_.reset();
// Map
map_sub_.reset(); // map_sub_ may access map_, so it should be reset earlier
if (map_ != NULL) {
map_free(map_);
map_ = nullptr;
}
first_map_received_ = false;
free_space_indices.resize(0);
// Transforms
tf_broadcaster_.reset();
tf_buffer_.reset();
// PubSub
pose_pub_.reset();
particle_cloud_pub_.reset();
// Odometry
motion_model_.reset();
// Particle Filter
pf_free(pf_);
pf_ = nullptr;
// Laser Scan
lasers_.clear();
lasers_update_.clear();
frame_to_laser_.clear();
force_update_ = true;
if (set_initial_pose_) {
set_parameter(
rclcpp::Parameter(
"initial_pose.x",
rclcpp::ParameterValue(last_published_pose_.pose.pose.position.x)));
set_parameter(
rclcpp::Parameter(
"initial_pose.y",
rclcpp::ParameterValue(last_published_pose_.pose.pose.position.y)));
set_parameter(
rclcpp::Parameter(
"initial_pose.z",
rclcpp::ParameterValue(last_published_pose_.pose.pose.position.z)));
set_parameter(
rclcpp::Parameter(
"initial_pose.yaw",
rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation))));
}
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
AmclNode::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Shutting down");
return nav2_util::CallbackReturn::SUCCESS;
}
bool
AmclNode::checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time)
{
rclcpp::Duration elapsed_time = now() - last_time;
if (elapsed_time.nanoseconds() * 1e-9 > check_interval.count()) {
return true;
}
return false;
}
#if NEW_UNIFORM_SAMPLING
std::vector<AmclNode::Point2D> AmclNode::free_space_indices;
#endif
bool
AmclNode::getOdomPose(
geometry_msgs::msg::PoseStamped & odom_pose,
double & x, double & y, double & yaw,
const rclcpp::Time & sensor_timestamp, const std::string & frame_id)
{
// Get the robot's pose
geometry_msgs::msg::PoseStamped ident;
ident.header.frame_id = nav2_util::strip_leading_slash(frame_id);
ident.header.stamp = sensor_timestamp;
tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
try {
tf_buffer_->transform(ident, odom_pose, odom_frame_id_);
} catch (tf2::TransformException & e) {
++scan_error_count_;
if (scan_error_count_ % 20 == 0) {
RCLCPP_ERROR(
get_logger(), "(%d) consecutive laser scan transforms failed: (%s)", scan_error_count_,
e.what());
}
return false;
}
scan_error_count_ = 0; // reset since we got a good transform
x = odom_pose.pose.position.x;
y = odom_pose.pose.position.y;
yaw = tf2::getYaw(odom_pose.pose.orientation);
return true;
}
pf_vector_t
AmclNode::uniformPoseGenerator(void * arg)
{
map_t * map = reinterpret_cast<map_t *>(arg);
#if NEW_UNIFORM_SAMPLING
unsigned int rand_index = drand48() * free_space_indices.size();
AmclNode::Point2D free_point = free_space_indices[rand_index];
pf_vector_t p;
p.v[0] = MAP_WXGX(map, free_point.x);
p.v[1] = MAP_WYGY(map, free_point.y);
p.v[2] = drand48() * 2 * M_PI - M_PI;
#else
double min_x, max_x, min_y, max_y;
min_x = (map->size_x * map->scale) / 2.0 - map->origin_x;
max_x = (map->size_x * map->scale) / 2.0 + map->origin_x;
min_y = (map->size_y * map->scale) / 2.0 - map->origin_y;
max_y = (map->size_y * map->scale) / 2.0 + map->origin_y;
pf_vector_t p;
RCLCPP_DEBUG(get_logger(), "Generating new uniform sample");
for (;; ) {
p.v[0] = min_x + drand48() * (max_x - min_x);
p.v[1] = min_y + drand48() * (max_y - min_y);
p.v[2] = drand48() * 2 * M_PI - M_PI;
// Check that it's a free cell
int i, j;
i = MAP_GXWX(map, p.v[0]);
j = MAP_GYWY(map, p.v[1]);
if (MAP_VALID(map, i, j) && (map->cells[MAP_INDEX(map, i, j)].occ_state == -1)) {
break;
}
}
#endif
return p;
}
void
AmclNode::globalLocalizationCallback(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);
RCLCPP_INFO(get_logger(), "Initializing with uniform distribution");
pf_init_model(
pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
reinterpret_cast<void *>(map_));
RCLCPP_INFO(get_logger(), "Global initialisation done!");
initial_pose_is_known_ = true;
pf_init_ = false;
}
void
AmclNode::initialPoseReceivedSrv(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>/*res*/)
{
initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
}
// force nomotion updates (amcl updating without requiring motion)
void
AmclNode::nomotionUpdateCallback(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
{
RCLCPP_INFO(get_logger(), "Requesting no-motion update");
force_update_ = true;
}
void
AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);
RCLCPP_INFO(get_logger(), "initialPoseReceived");
if (!nav2_util::validateMsg(*msg)) {
RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting.");
return;
}
if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) {
RCLCPP_WARN(
get_logger(),
"Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
nav2_util::strip_leading_slash(msg->header.frame_id).c_str(),
global_frame_id_.c_str());
return;
}
if (first_map_received_ && (abs(msg->pose.pose.position.x) > map_->size_x ||
abs(msg->pose.pose.position.y) > map_->size_y))
{
RCLCPP_ERROR(
get_logger(), "Received initialpose from message is out of the size of map. Rejecting.");
return;
}
// Overriding last published pose to initial pose
last_published_pose_ = *msg;
if (!active_) {
init_pose_received_on_inactive = true;
RCLCPP_WARN(
get_logger(), "Received initial pose request, "
"but AMCL is not yet in the active state");
return;
}
handleInitialPose(*msg);
}
void
AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);
// In case the client sent us a pose estimate in the past, integrate the
// intervening odometric change.
geometry_msgs::msg::TransformStamped tx_odom;
try {
rclcpp::Time rclcpp_time = now();
tf2::TimePoint tf2_time(std::chrono::nanoseconds(rclcpp_time.nanoseconds()));
// Check if the transform is available
tx_odom = tf_buffer_->lookupTransform(
base_frame_id_, tf2_ros::fromMsg(msg.header.stamp),
base_frame_id_, tf2_time, odom_frame_id_);
} catch (tf2::TransformException & e) {
// If we've never sent a transform, then this is normal, because the
// global_frame_id_ frame doesn't exist. We only care about in-time
// transformation for on-the-move pose-setting, so ignoring this
// startup condition doesn't really cost us anything.
if (sent_first_transform_) {
RCLCPP_WARN(get_logger(), "Failed to transform initial pose in time (%s)", e.what());
}
tf2::impl::Converter<false, true>::convert(tf2::Transform::getIdentity(), tx_odom.transform);
}
tf2::Transform tx_odom_tf2;
tf2::impl::Converter<true, false>::convert(tx_odom.transform, tx_odom_tf2);
tf2::Transform pose_old;
tf2::impl::Converter<true, false>::convert(msg.pose.pose, pose_old);
tf2::Transform pose_new = pose_old * tx_odom_tf2;
// Transform into the global frame
RCLCPP_INFO(
get_logger(), "Setting pose (%.6f): %.3f %.3f %.3f",
now().nanoseconds() * 1e-9,
pose_new.getOrigin().x(),
pose_new.getOrigin().y(),
tf2::getYaw(pose_new.getRotation()));
// Re-initialize the filter
pf_vector_t pf_init_pose_mean = pf_vector_zero();
pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
// Copy in the covariance, converting from 6-D to 3-D
for (int i = 0; i < 2; i++) {
for (int j = 0; j < 2; j++) {
pf_init_pose_cov.m[i][j] = msg.pose.covariance[6 * i + j];
}
}
pf_init_pose_cov.m[2][2] = msg.pose.covariance[6 * 5 + 5];
pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
pf_init_ = false;
init_pose_received_on_inactive = false;
initial_pose_is_known_ = true;
}
void
AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);
// Since the sensor data is continually being published by the simulator or robot,
// we don't want our callbacks to fire until we're in the active state
if (!active_) {return;}
if (!first_map_received_) {
if (checkElapsedTime(2s, last_time_printed_msg_)) {
RCLCPP_WARN(get_logger(), "Waiting for map....");
last_time_printed_msg_ = now();
}
return;
}
std::string laser_scan_frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id);
last_laser_received_ts_ = now();
int laser_index = -1;
geometry_msgs::msg::PoseStamped laser_pose;
// Do we have the base->base_laser Tx yet?
if (frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) {
if (!addNewScanner(laser_index, laser_scan, laser_scan_frame_id, laser_pose)) {
return; // could not find transform
}
} else {
// we have the laser pose, retrieve laser index
laser_index = frame_to_laser_[laser_scan->header.frame_id];
}
// Where was the robot when this scan was taken?
pf_vector_t pose;
if (!getOdomPose(
latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
laser_scan->header.stamp, base_frame_id_))
{
RCLCPP_ERROR(get_logger(), "Couldn't determine robot's pose associated with laser scan");
return;
}
pf_vector_t delta = pf_vector_zero();
bool force_publication = false;
if (!pf_init_) {
// Pose at last filter update
pf_odom_pose_ = pose;
pf_init_ = true;
for (unsigned int i = 0; i < lasers_update_.size(); i++) {
lasers_update_[i] = true;
}
force_publication = true;
resample_count_ = 0;
} else {
// Set the laser update flags
if (shouldUpdateFilter(pose, delta)) {
for (unsigned int i = 0; i < lasers_update_.size(); i++) {
lasers_update_[i] = true;
}
}
if (lasers_update_[laser_index]) {
motion_model_->odometryUpdate(pf_, pose, delta);
}
force_update_ = false;
}
bool resampled = false;
// If the robot has moved, update the filter
if (lasers_update_[laser_index]) {
updateFilter(laser_index, laser_scan, pose);
// Resample the particles
if (!(++resample_count_ % resample_interval_)) {
pf_update_resample(pf_, reinterpret_cast<void *>(map_));
resampled = true;
}
pf_sample_set_t * set = pf_->sets + pf_->current_set;
RCLCPP_DEBUG(get_logger(), "Num samples: %d\n", set->sample_count);
if (!force_update_) {
publishParticleCloud(set);
}
}
if (resampled || force_publication || !first_pose_sent_) {
amcl_hyp_t max_weight_hyps;
std::vector<amcl_hyp_t> hyps;
int max_weight_hyp = -1;
if (getMaxWeightHyp(hyps, max_weight_hyps, max_weight_hyp)) {
publishAmclPose(laser_scan, hyps, max_weight_hyp);
calculateMaptoOdomTransform(laser_scan, hyps, max_weight_hyp);
if (tf_broadcast_ == true) {
// We want to send a transform that is good up until a
// tolerance time so that odom can be used
auto stamp = tf2_ros::fromMsg(laser_scan->header.stamp);
tf2::TimePoint transform_expiration = stamp + transform_tolerance_;
sendMapToOdomTransform(transform_expiration);
sent_first_transform_ = true;
}
} else {
RCLCPP_ERROR(get_logger(), "No pose!");
}
} else if (latest_tf_valid_) {
if (tf_broadcast_ == true) {
// Nothing changed, so we'll just republish the last transform, to keep
// everybody happy.
tf2::TimePoint transform_expiration = tf2_ros::fromMsg(laser_scan->header.stamp) +
transform_tolerance_;
sendMapToOdomTransform(transform_expiration);
}
}
}
bool AmclNode::addNewScanner(
int & laser_index,
const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
const std::string & laser_scan_frame_id,
geometry_msgs::msg::PoseStamped & laser_pose)
{
lasers_.push_back(createLaserObject());
lasers_update_.push_back(true);
laser_index = frame_to_laser_.size();
geometry_msgs::msg::PoseStamped ident;
ident.header.frame_id = laser_scan_frame_id;
ident.header.stamp = rclcpp::Time();
tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
try {
tf_buffer_->transform(ident, laser_pose, base_frame_id_, transform_tolerance_);
} catch (tf2::TransformException & e) {
RCLCPP_ERROR(
get_logger(), "Couldn't transform from %s to %s, "
"even though the message notifier is in use: (%s)",
laser_scan->header.frame_id.c_str(),
base_frame_id_.c_str(), e.what());
return false;
}
pf_vector_t laser_pose_v;
laser_pose_v.v[0] = laser_pose.pose.position.x;
laser_pose_v.v[1] = laser_pose.pose.position.y;
// laser mounting angle gets computed later -> set to 0 here!
laser_pose_v.v[2] = 0;
lasers_[laser_index]->SetLaserPose(laser_pose_v);
frame_to_laser_[laser_scan->header.frame_id] = laser_index;
return true;
}
bool AmclNode::shouldUpdateFilter(const pf_vector_t pose, pf_vector_t & delta)
{
delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
delta.v[2] = angleutils::angle_diff(pose.v[2], pf_odom_pose_.v[2]);
// See if we should update the filter
bool update = fabs(delta.v[0]) > d_thresh_ ||
fabs(delta.v[1]) > d_thresh_ ||
fabs(delta.v[2]) > a_thresh_;
update = update || force_update_;
return update;
}
bool AmclNode::updateFilter(
const int & laser_index,
const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
const pf_vector_t & pose)
{
nav2_amcl::LaserData ldata;
ldata.laser = lasers_[laser_index];
ldata.range_count = laser_scan->ranges.size();
// To account for lasers that are mounted upside-down, we determine the
// min, max, and increment angles of the laser in the base frame.
//
// Construct min and max angles of laser, in the base_link frame.
// Here we set the roll pich yaw of the lasers. We assume roll and pich are zero.
geometry_msgs::msg::QuaternionStamped min_q, inc_q;
min_q.header.stamp = laser_scan->header.stamp;
min_q.header.frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id);
min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min);
inc_q.header = min_q.header;
inc_q.quaternion = orientationAroundZAxis(laser_scan->angle_min + laser_scan->angle_increment);
try {
tf_buffer_->transform(min_q, min_q, base_frame_id_);
tf_buffer_->transform(inc_q, inc_q, base_frame_id_);
} catch (tf2::TransformException & e) {
RCLCPP_WARN(
get_logger(), "Unable to transform min/max laser angles into base frame: %s",
e.what());
return false;
}
double angle_min = tf2::getYaw(min_q.quaternion);
double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
// wrapping angle to [-pi .. pi]
angle_increment = fmod(angle_increment + 5 * M_PI, 2 * M_PI) - M_PI;
RCLCPP_DEBUG(
get_logger(), "Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
angle_increment);
// Check the validity of range_max, must > 0.0
if (laser_scan->range_max <= 0.0) {
RCLCPP_WARN(
get_logger(), "wrong range_max of laser_scan data: %f. The message could be malformed."
" Ignore this message and stop updating.",
laser_scan->range_max);
return false;
}
// Apply range min/max thresholds, if the user supplied them
if (laser_max_range_ > 0.0) {
ldata.range_max = std::min(laser_scan->range_max, static_cast<float>(laser_max_range_));
} else {
ldata.range_max = laser_scan->range_max;
}
double range_min;
if (laser_min_range_ > 0.0) {
range_min = std::max(laser_scan->range_min, static_cast<float>(laser_min_range_));
} else {
range_min = laser_scan->range_min;
}
// The LaserData destructor will free this memory
ldata.ranges = new double[ldata.range_count][2];
for (int i = 0; i < ldata.range_count; i++) {
// amcl doesn't (yet) have a concept of min range. So we'll map short
// readings to max range.
if (laser_scan->ranges[i] <= range_min) {
ldata.ranges[i][0] = ldata.range_max;
} else {
ldata.ranges[i][0] = laser_scan->ranges[i];
}
// Compute bearing
ldata.ranges[i][1] = angle_min +
(i * angle_increment);
}
lasers_[laser_index]->sensorUpdate(pf_, reinterpret_cast<nav2_amcl::LaserData *>(&ldata));
lasers_update_[laser_index] = false;
pf_odom_pose_ = pose;
return true;
}
void
AmclNode::publishParticleCloud(const pf_sample_set_t * set)
{
// If initial pose is not known, AMCL does not know the current pose
if (!initial_pose_is_known_) {return;}
auto cloud_with_weights_msg = std::make_unique<nav2_msgs::msg::ParticleCloud>();
cloud_with_weights_msg->header.stamp = this->now();
cloud_with_weights_msg->header.frame_id = global_frame_id_;
cloud_with_weights_msg->particles.resize(set->sample_count);
for (int i = 0; i < set->sample_count; i++) {
cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
cloud_with_weights_msg->particles[i].pose.position.z = 0;
cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
set->samples[i].pose.v[2]);
cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
}
particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
}
bool
AmclNode::getMaxWeightHyp(
std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
int & max_weight_hyp)
{
// Read out the current hypotheses
double max_weight = 0.0;
hyps.resize(pf_->sets[pf_->current_set].cluster_count);
for (int hyp_count = 0;
hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
{
double weight;
pf_vector_t pose_mean;
pf_matrix_t pose_cov;
if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) {
RCLCPP_ERROR(get_logger(), "Couldn't get stats on cluster %d", hyp_count);
return false;
}
hyps[hyp_count].weight = weight;
hyps[hyp_count].pf_pose_mean = pose_mean;
hyps[hyp_count].pf_pose_cov = pose_cov;
if (hyps[hyp_count].weight > max_weight) {
max_weight = hyps[hyp_count].weight;
max_weight_hyp = hyp_count;
}
}
if (max_weight > 0.0) {
RCLCPP_DEBUG(
get_logger(), "Max weight pose: %.3f %.3f %.3f",
hyps[max_weight_hyp].pf_pose_mean.v[0],
hyps[max_weight_hyp].pf_pose_mean.v[1],
hyps[max_weight_hyp].pf_pose_mean.v[2]);
max_weight_hyps = hyps[max_weight_hyp];
return true;
}
return false;
}
void
AmclNode::publishAmclPose(
const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
const std::vector<amcl_hyp_t> & hyps, const int & max_weight_hyp)
{
// If initial pose is not known, AMCL does not know the current pose
if (!initial_pose_is_known_) {
if (checkElapsedTime(2s, last_time_printed_msg_)) {
RCLCPP_WARN(
get_logger(), "AMCL cannot publish a pose or update the transform. "
"Please set the initial pose...");
last_time_printed_msg_ = now();
}
return;
}
auto p = std::make_unique<geometry_msgs::msg::PoseWithCovarianceStamped>();
// Fill in the header
p->header.frame_id = global_frame_id_;
p->header.stamp = laser_scan->header.stamp;
// Copy in the pose
p->pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
p->pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
p->pose.pose.orientation = orientationAroundZAxis(hyps[max_weight_hyp].pf_pose_mean.v[2]);
// Copy in the covariance, converting from 3-D to 6-D
pf_sample_set_t * set = pf_->sets + pf_->current_set;
for (int i = 0; i < 2; i++) {
for (int j = 0; j < 2; j++) {
// Report the overall filter covariance, rather than the
// covariance for the highest-weight cluster
// p->covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
p->pose.covariance[6 * i + j] = set->cov.m[i][j];
}
}
p->pose.covariance[6 * 5 + 5] = set->cov.m[2][2];
float temp = 0.0;
for (auto covariance_value : p->pose.covariance) {
temp += covariance_value;
}
temp += p->pose.pose.position.x + p->pose.pose.position.y;
if (!std::isnan(temp)) {
RCLCPP_DEBUG(get_logger(), "Publishing pose");
last_published_pose_ = *p;
first_pose_sent_ = true;
pose_pub_->publish(std::move(p));
} else {
RCLCPP_WARN(
get_logger(), "AMCL covariance or pose is NaN, likely due to an invalid "
"configuration or faulty sensor measurements! Pose is not available!");
}
RCLCPP_DEBUG(
get_logger(), "New pose: %6.3f %6.3f %6.3f",
hyps[max_weight_hyp].pf_pose_mean.v[0],
hyps[max_weight_hyp].pf_pose_mean.v[1],
hyps[max_weight_hyp].pf_pose_mean.v[2]);
}
void
AmclNode::calculateMaptoOdomTransform(
const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
const std::vector<amcl_hyp_t> & hyps, const int & max_weight_hyp)
{
// subtracting base to odom from map to base and send map to odom instead
geometry_msgs::msg::PoseStamped odom_to_map;