-
Notifications
You must be signed in to change notification settings - Fork 1.8k
/
Copy pathamcl_node.cpp
1656 lines (1433 loc) · 53.3 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 <algorithm>
#include <vector>
#include <map>
#include <cmath>
#include <memory>
#include <boost/bind.hpp>
#include <boost/thread/mutex.hpp>
// Signal handling
#include <signal.h>
#include "amcl/map/map.h"
#include "amcl/pf/pf.h"
#include "amcl/sensors/amcl_odom.h"
#include "amcl/sensors/amcl_laser.h"
#include "portable_utils.hpp"
#include "ros/assert.h"
// roscpp
#include "ros/ros.h"
// Messages that I need
#include "sensor_msgs/LaserScan.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/Pose.h"
#include "geometry_msgs/PoseStamped.h"
#include "nav_msgs/GetMap.h"
#include "nav_msgs/SetMap.h"
#include "std_srvs/Empty.h"
// For transform support
#include "tf2/LinearMath/Transform.h"
#include "tf2/convert.h"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.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 "message_filters/subscriber.h"
// Dynamic_reconfigure
#include "dynamic_reconfigure/server.h"
#include "amcl/AMCLConfig.h"
// Allows AMCL to run from bag file
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <boost/foreach.hpp>
// For monitoring the estimator
#include <diagnostic_updater/diagnostic_updater.h>
#define NEW_UNIFORM_SAMPLING 1
using namespace amcl;
// Pose hypothesis
typedef struct
{
// Total weight (weights sum to 1)
double weight;
// Mean of pose esimate
pf_vector_t pf_pose_mean;
// Covariance of pose estimate
pf_matrix_t pf_pose_cov;
} amcl_hyp_t;
static double
normalize(double z)
{
return atan2(sin(z),cos(z));
}
static double
angle_diff(double a, double b)
{
double d1, d2;
a = normalize(a);
b = normalize(b);
d1 = a-b;
d2 = 2*M_PI - fabs(d1);
if(d1 > 0)
d2 *= -1.0;
if(fabs(d1) < fabs(d2))
return(d1);
else
return(d2);
}
static const std::string scan_topic_ = "scan";
/* This function is only useful to have the whole code work
* with old rosbags that have trailing slashes for their frames
*/
inline
std::string stripSlash(const std::string& in)
{
std::string out = in;
if ( ( !in.empty() ) && (in[0] == '/') )
out.erase(0,1);
return out;
}
class AmclNode
{
public:
AmclNode();
~AmclNode();
/**
* @brief Uses TF and LaserScan messages from bag file to drive AMCL instead
* @param in_bag_fn input bagfile
* @param trigger_global_localization whether to trigger global localization
* before starting to process the bagfile
*/
void runFromBag(const std::string &in_bag_fn, bool trigger_global_localization = false);
int process();
void savePoseToServer();
private:
std::shared_ptr<tf2_ros::TransformBroadcaster> tfb_;
std::shared_ptr<tf2_ros::TransformListener> tfl_;
std::shared_ptr<tf2_ros::Buffer> tf_;
bool sent_first_transform_;
tf2::Transform latest_tf_;
bool latest_tf_valid_;
// Pose-generating function used to uniformly distribute particles over
// the map
static pf_vector_t uniformPoseGenerator(void* arg);
#if NEW_UNIFORM_SAMPLING
static std::vector<std::pair<int,int> > free_space_indices;
#endif
// Callbacks
bool globalLocalizationCallback(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res);
bool nomotionUpdateCallback(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res);
bool setMapCallback(nav_msgs::SetMap::Request& req,
nav_msgs::SetMap::Response& res);
void laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan);
void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
void handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped& msg);
void mapReceived(const nav_msgs::OccupancyGridConstPtr& msg);
void handleMapMessage(const nav_msgs::OccupancyGrid& msg);
void freeMapDependentMemory();
map_t* convertMap( const nav_msgs::OccupancyGrid& map_msg );
void updatePoseFromServer();
void applyInitialPose();
//parameter for which odom to use
std::string odom_frame_id_;
//paramater to store latest odom pose
geometry_msgs::PoseStamped latest_odom_pose_;
//parameter for which base to use
std::string base_frame_id_;
std::string global_frame_id_;
bool use_map_topic_;
bool first_map_only_;
ros::Duration gui_publish_period;
ros::Time save_pose_last_time;
ros::Duration save_pose_period;
geometry_msgs::PoseWithCovarianceStamped last_published_pose;
map_t* map_;
char* mapdata;
int sx, sy;
double resolution;
message_filters::Subscriber<sensor_msgs::LaserScan>* laser_scan_sub_;
tf2_ros::MessageFilter<sensor_msgs::LaserScan>* laser_scan_filter_;
ros::Subscriber initial_pose_sub_;
std::vector< AMCLLaser* > lasers_;
std::vector< bool > lasers_update_;
std::map< std::string, int > frame_to_laser_;
// Particle filter
pf_t *pf_;
double pf_err_, pf_z_;
bool pf_init_;
pf_vector_t pf_odom_pose_;
double d_thresh_, a_thresh_;
int resample_interval_;
int resample_count_;
double laser_min_range_;
double laser_max_range_;
//Nomotion update control
bool m_force_update; // used to temporarily let amcl update samples even when no motion occurs...
AMCLOdom* odom_;
AMCLLaser* laser_;
ros::Duration cloud_pub_interval;
ros::Time last_cloud_pub_time;
// For slowing play-back when reading directly from a bag file
ros::WallDuration bag_scan_period_;
void requestMap();
// Helper to get odometric pose from transform system
bool getOdomPose(geometry_msgs::PoseStamped& pose,
double& x, double& y, double& yaw,
const ros::Time& t, const std::string& f);
//time for tolerance on the published transform,
//basically defines how long a map->odom transform is good for
ros::Duration transform_tolerance_;
ros::NodeHandle nh_;
ros::NodeHandle private_nh_;
ros::Publisher pose_pub_;
ros::Publisher particlecloud_pub_;
ros::ServiceServer global_loc_srv_;
ros::ServiceServer nomotion_update_srv_; //to let amcl update samples without requiring motion
ros::ServiceServer set_map_srv_;
ros::Subscriber initial_pose_sub_old_;
ros::Subscriber map_sub_;
diagnostic_updater::Updater diagnosic_updater_;
void standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& diagnostic_status);
double std_warn_level_x_;
double std_warn_level_y_;
double std_warn_level_yaw_;
amcl_hyp_t* initial_pose_hyp_;
bool first_map_received_;
bool first_reconfigure_call_;
boost::recursive_mutex configuration_mutex_;
dynamic_reconfigure::Server<amcl::AMCLConfig> *dsrv_;
amcl::AMCLConfig default_config_;
ros::Timer check_laser_timer_;
int max_beams_, min_particles_, max_particles_;
double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
double alpha_slow_, alpha_fast_;
double z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_;
//beam skip related params
bool do_beamskip_;
double beam_skip_distance_, beam_skip_threshold_, beam_skip_error_threshold_;
double laser_likelihood_max_dist_;
odom_model_t odom_model_type_;
double init_pose_[3];
double init_cov_[3];
laser_model_t laser_model_type_;
bool tf_broadcast_;
bool force_update_after_initialpose_;
bool force_update_after_set_map_;
bool selective_resampling_;
void reconfigureCB(amcl::AMCLConfig &config, uint32_t level);
ros::Time last_laser_received_ts_;
ros::Duration laser_check_interval_;
void checkLaserReceived(const ros::TimerEvent& event);
};
#if NEW_UNIFORM_SAMPLING
std::vector<std::pair<int,int> > AmclNode::free_space_indices;
#endif
#define USAGE "USAGE: amcl"
boost::shared_ptr<AmclNode> amcl_node_ptr;
void sigintHandler(int sig)
{
// Save latest pose as we're shutting down.
amcl_node_ptr->savePoseToServer();
ros::shutdown();
}
int
main(int argc, char** argv)
{
ros::init(argc, argv, "amcl");
ros::NodeHandle nh;
// Override default sigint handler
signal(SIGINT, sigintHandler);
// Make our node available to sigintHandler
amcl_node_ptr.reset(new AmclNode());
if (argc == 1)
{
// run using ROS input
ros::spin();
}
else if ((argc >= 3) && (std::string(argv[1]) == "--run-from-bag"))
{
if (argc == 3)
{
amcl_node_ptr->runFromBag(argv[2]);
}
else if ((argc == 4) && (std::string(argv[3]) == "--global-localization"))
{
amcl_node_ptr->runFromBag(argv[2], true);
}
}
// Without this, our boost locks are not shut down nicely
amcl_node_ptr.reset();
// To quote Morgan, Hooray!
return(0);
}
AmclNode::AmclNode() :
sent_first_transform_(false),
latest_tf_valid_(false),
map_(NULL),
pf_(NULL),
resample_count_(0),
odom_(NULL),
laser_(NULL),
private_nh_("~"),
initial_pose_hyp_(NULL),
first_map_received_(false),
first_reconfigure_call_(true)
{
boost::recursive_mutex::scoped_lock l(configuration_mutex_);
// Grab params off the param server
private_nh_.param("use_map_topic", use_map_topic_, false);
private_nh_.param("first_map_only", first_map_only_, false);
double tmp;
private_nh_.param("gui_publish_rate", tmp, -1.0);
gui_publish_period = ros::Duration(1.0/tmp);
private_nh_.param("save_pose_rate", tmp, 0.5);
save_pose_period = ros::Duration(1.0/tmp);
private_nh_.param("laser_min_range", laser_min_range_, -1.0);
private_nh_.param("laser_max_range", laser_max_range_, -1.0);
private_nh_.param("laser_max_beams", max_beams_, 30);
private_nh_.param("min_particles", min_particles_, 100);
private_nh_.param("max_particles", max_particles_, 5000);
private_nh_.param("kld_err", pf_err_, 0.01);
private_nh_.param("kld_z", pf_z_, 0.99);
private_nh_.param("odom_alpha1", alpha1_, 0.2);
private_nh_.param("odom_alpha2", alpha2_, 0.2);
private_nh_.param("odom_alpha3", alpha3_, 0.2);
private_nh_.param("odom_alpha4", alpha4_, 0.2);
private_nh_.param("odom_alpha5", alpha5_, 0.2);
private_nh_.param("do_beamskip", do_beamskip_, false);
private_nh_.param("beam_skip_distance", beam_skip_distance_, 0.5);
private_nh_.param("beam_skip_threshold", beam_skip_threshold_, 0.3);
if (private_nh_.hasParam("beam_skip_error_threshold_"))
{
private_nh_.param("beam_skip_error_threshold_", beam_skip_error_threshold_);
}
else
{
private_nh_.param("beam_skip_error_threshold", beam_skip_error_threshold_, 0.9);
}
private_nh_.param("laser_z_hit", z_hit_, 0.95);
private_nh_.param("laser_z_short", z_short_, 0.1);
private_nh_.param("laser_z_max", z_max_, 0.05);
private_nh_.param("laser_z_rand", z_rand_, 0.05);
private_nh_.param("laser_sigma_hit", sigma_hit_, 0.2);
private_nh_.param("laser_lambda_short", lambda_short_, 0.1);
private_nh_.param("laser_likelihood_max_dist", laser_likelihood_max_dist_, 2.0);
std::string tmp_model_type;
private_nh_.param("laser_model_type", tmp_model_type, std::string("likelihood_field"));
if(tmp_model_type == "beam")
laser_model_type_ = LASER_MODEL_BEAM;
else if(tmp_model_type == "likelihood_field")
laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
else if(tmp_model_type == "likelihood_field_prob"){
laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD_PROB;
}
else
{
ROS_WARN("Unknown laser model type \"%s\"; defaulting to likelihood_field model",
tmp_model_type.c_str());
laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
}
private_nh_.param("odom_model_type", tmp_model_type, std::string("diff"));
if(tmp_model_type == "diff")
odom_model_type_ = ODOM_MODEL_DIFF;
else if(tmp_model_type == "omni")
odom_model_type_ = ODOM_MODEL_OMNI;
else if(tmp_model_type == "diff-corrected")
odom_model_type_ = ODOM_MODEL_DIFF_CORRECTED;
else if(tmp_model_type == "omni-corrected")
odom_model_type_ = ODOM_MODEL_OMNI_CORRECTED;
else
{
ROS_WARN("Unknown odom model type \"%s\"; defaulting to diff model",
tmp_model_type.c_str());
odom_model_type_ = ODOM_MODEL_DIFF;
}
private_nh_.param("update_min_d", d_thresh_, 0.2);
private_nh_.param("update_min_a", a_thresh_, M_PI/6.0);
private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom"));
private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link"));
private_nh_.param("global_frame_id", global_frame_id_, std::string("map"));
private_nh_.param("resample_interval", resample_interval_, 2);
private_nh_.param("selective_resampling", selective_resampling_, false);
double tmp_tol;
private_nh_.param("transform_tolerance", tmp_tol, 0.1);
private_nh_.param("recovery_alpha_slow", alpha_slow_, 0.001);
private_nh_.param("recovery_alpha_fast", alpha_fast_, 0.1);
private_nh_.param("tf_broadcast", tf_broadcast_, true);
private_nh_.param("force_update_after_initialpose", force_update_after_initialpose_, false);
private_nh_.param("force_update_after_set_map", force_update_after_set_map_, false);
// For diagnostics
private_nh_.param("std_warn_level_x", std_warn_level_x_, 0.2);
private_nh_.param("std_warn_level_y", std_warn_level_y_, 0.2);
private_nh_.param("std_warn_level_yaw", std_warn_level_yaw_, 0.1);
transform_tolerance_.fromSec(tmp_tol);
{
double bag_scan_period;
private_nh_.param("bag_scan_period", bag_scan_period, -1.0);
bag_scan_period_.fromSec(bag_scan_period);
}
odom_frame_id_ = stripSlash(odom_frame_id_);
base_frame_id_ = stripSlash(base_frame_id_);
global_frame_id_ = stripSlash(global_frame_id_);
updatePoseFromServer();
cloud_pub_interval.fromSec(1.0);
tfb_.reset(new tf2_ros::TransformBroadcaster());
tf_.reset(new tf2_ros::Buffer());
tfl_.reset(new tf2_ros::TransformListener(*tf_));
pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 2, true);
particlecloud_pub_ = nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 2, true);
global_loc_srv_ = nh_.advertiseService("global_localization",
&AmclNode::globalLocalizationCallback,
this);
nomotion_update_srv_= nh_.advertiseService("request_nomotion_update", &AmclNode::nomotionUpdateCallback, this);
set_map_srv_= nh_.advertiseService("set_map", &AmclNode::setMapCallback, this);
laser_scan_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(nh_, scan_topic_, 100);
laser_scan_filter_ =
new tf2_ros::MessageFilter<sensor_msgs::LaserScan>(*laser_scan_sub_,
*tf_,
odom_frame_id_,
100,
nh_);
laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
this, _1));
initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
if(use_map_topic_) {
map_sub_ = nh_.subscribe("map", 1, &AmclNode::mapReceived, this);
ROS_INFO("Subscribed to map topic.");
} else {
requestMap();
}
m_force_update = false;
dsrv_ = new dynamic_reconfigure::Server<amcl::AMCLConfig>(ros::NodeHandle("~"));
dynamic_reconfigure::Server<amcl::AMCLConfig>::CallbackType cb = boost::bind(&AmclNode::reconfigureCB, this, _1, _2);
dsrv_->setCallback(cb);
// 15s timer to warn on lack of receipt of laser scans, #5209
laser_check_interval_ = ros::Duration(15.0);
check_laser_timer_ = nh_.createTimer(laser_check_interval_,
boost::bind(&AmclNode::checkLaserReceived, this, _1));
diagnosic_updater_.setHardwareID("None");
diagnosic_updater_.add("Standard deviation", this, &AmclNode::standardDeviationDiagnostics);
}
void AmclNode::reconfigureCB(AMCLConfig &config, uint32_t level)
{
boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
//we don't want to do anything on the first call
//which corresponds to startup
if(first_reconfigure_call_)
{
first_reconfigure_call_ = false;
default_config_ = config;
return;
}
if(config.restore_defaults) {
config = default_config_;
//avoid looping
config.restore_defaults = false;
}
d_thresh_ = config.update_min_d;
a_thresh_ = config.update_min_a;
resample_interval_ = config.resample_interval;
laser_min_range_ = config.laser_min_range;
laser_max_range_ = config.laser_max_range;
gui_publish_period = ros::Duration(1.0/config.gui_publish_rate);
save_pose_period = ros::Duration(1.0/config.save_pose_rate);
transform_tolerance_.fromSec(config.transform_tolerance);
max_beams_ = config.laser_max_beams;
alpha1_ = config.odom_alpha1;
alpha2_ = config.odom_alpha2;
alpha3_ = config.odom_alpha3;
alpha4_ = config.odom_alpha4;
alpha5_ = config.odom_alpha5;
z_hit_ = config.laser_z_hit;
z_short_ = config.laser_z_short;
z_max_ = config.laser_z_max;
z_rand_ = config.laser_z_rand;
sigma_hit_ = config.laser_sigma_hit;
lambda_short_ = config.laser_lambda_short;
laser_likelihood_max_dist_ = config.laser_likelihood_max_dist;
if(config.laser_model_type == "beam")
laser_model_type_ = LASER_MODEL_BEAM;
else if(config.laser_model_type == "likelihood_field")
laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
else if(config.laser_model_type == "likelihood_field_prob")
laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD_PROB;
if(config.odom_model_type == "diff")
odom_model_type_ = ODOM_MODEL_DIFF;
else if(config.odom_model_type == "omni")
odom_model_type_ = ODOM_MODEL_OMNI;
else if(config.odom_model_type == "diff-corrected")
odom_model_type_ = ODOM_MODEL_DIFF_CORRECTED;
else if(config.odom_model_type == "omni-corrected")
odom_model_type_ = ODOM_MODEL_OMNI_CORRECTED;
if(config.min_particles > config.max_particles)
{
ROS_WARN("You've set min_particles to be greater than max particles, this isn't allowed so they'll be set to be equal.");
config.max_particles = config.min_particles;
}
min_particles_ = config.min_particles;
max_particles_ = config.max_particles;
alpha_slow_ = config.recovery_alpha_slow;
alpha_fast_ = config.recovery_alpha_fast;
tf_broadcast_ = config.tf_broadcast;
force_update_after_initialpose_ = config.force_update_after_initialpose;
force_update_after_set_map_ = config.force_update_after_set_map;
do_beamskip_= config.do_beamskip;
beam_skip_distance_ = config.beam_skip_distance;
beam_skip_threshold_ = config.beam_skip_threshold;
// Clear queued laser objects so that their parameters get updated
lasers_.clear();
lasers_update_.clear();
frame_to_laser_.clear();
if( pf_ != NULL )
{
pf_free( pf_ );
pf_ = NULL;
}
pf_ = pf_alloc(min_particles_, max_particles_,
alpha_slow_, alpha_fast_,
(pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
(void *)map_);
pf_set_selective_resampling(pf_, selective_resampling_);
pf_err_ = config.kld_err;
pf_z_ = config.kld_z;
pf_->pop_err = pf_err_;
pf_->pop_z = pf_z_;
// Initialize the filter
pf_vector_t pf_init_pose_mean = pf_vector_zero();
pf_init_pose_mean.v[0] = last_published_pose.pose.pose.position.x;
pf_init_pose_mean.v[1] = last_published_pose.pose.pose.position.y;
pf_init_pose_mean.v[2] = tf2::getYaw(last_published_pose.pose.pose.orientation);
pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
pf_init_pose_cov.m[0][0] = last_published_pose.pose.covariance[6*0+0];
pf_init_pose_cov.m[1][1] = last_published_pose.pose.covariance[6*1+1];
pf_init_pose_cov.m[2][2] = last_published_pose.pose.covariance[6*5+5];
pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
pf_init_ = false;
// Instantiate the sensor objects
// Odometry
delete odom_;
odom_ = new AMCLOdom();
ROS_ASSERT(odom_);
odom_->SetModel( odom_model_type_, alpha1_, alpha2_, alpha3_, alpha4_, alpha5_ );
// Laser
delete laser_;
laser_ = new AMCLLaser(max_beams_, map_);
ROS_ASSERT(laser_);
if(laser_model_type_ == LASER_MODEL_BEAM)
laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_,
sigma_hit_, lambda_short_, 0.0);
else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD_PROB){
ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
laser_->SetModelLikelihoodFieldProb(z_hit_, z_rand_, sigma_hit_,
laser_likelihood_max_dist_,
do_beamskip_, beam_skip_distance_,
beam_skip_threshold_, beam_skip_error_threshold_);
ROS_INFO("Done initializing likelihood field model with probabilities.");
}
else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD){
ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_,
laser_likelihood_max_dist_);
ROS_INFO("Done initializing likelihood field model.");
}
odom_frame_id_ = stripSlash(config.odom_frame_id);
base_frame_id_ = stripSlash(config.base_frame_id);
global_frame_id_ = stripSlash(config.global_frame_id);
delete laser_scan_filter_;
laser_scan_filter_ =
new tf2_ros::MessageFilter<sensor_msgs::LaserScan>(*laser_scan_sub_,
*tf_,
odom_frame_id_,
100,
nh_);
laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
this, _1));
initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
}
void AmclNode::runFromBag(const std::string &in_bag_fn, bool trigger_global_localization)
{
rosbag::Bag bag;
bag.open(in_bag_fn, rosbag::bagmode::Read);
std::vector<std::string> topics;
topics.push_back(std::string("tf"));
std::string scan_topic_name = "base_scan"; // TODO determine what topic this actually is from ROS
topics.push_back(scan_topic_name);
rosbag::View view(bag, rosbag::TopicQuery(topics));
ros::Publisher laser_pub = nh_.advertise<sensor_msgs::LaserScan>(scan_topic_name, 100);
ros::Publisher tf_pub = nh_.advertise<tf2_msgs::TFMessage>("/tf", 100);
// Sleep for a second to let all subscribers connect
ros::WallDuration(1.0).sleep();
ros::WallTime start(ros::WallTime::now());
// Wait for map
while (ros::ok())
{
{
boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
if (map_)
{
ROS_INFO("Map is ready");
break;
}
}
ROS_INFO("Waiting for the map...");
ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(1.0));
}
if (trigger_global_localization)
{
std_srvs::Empty empty_srv;
globalLocalizationCallback(empty_srv.request, empty_srv.response);
}
BOOST_FOREACH(rosbag::MessageInstance const msg, view)
{
if (!ros::ok())
{
break;
}
// Process any ros messages or callbacks at this point
ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration());
tf2_msgs::TFMessage::ConstPtr tf_msg = msg.instantiate<tf2_msgs::TFMessage>();
if (tf_msg != NULL)
{
tf_pub.publish(msg);
for (size_t ii=0; ii<tf_msg->transforms.size(); ++ii)
{
tf_->setTransform(tf_msg->transforms[ii], "rosbag_authority");
}
continue;
}
sensor_msgs::LaserScan::ConstPtr base_scan = msg.instantiate<sensor_msgs::LaserScan>();
if (base_scan != NULL)
{
laser_pub.publish(msg);
laser_scan_filter_->add(base_scan);
if (bag_scan_period_ > ros::WallDuration(0))
{
bag_scan_period_.sleep();
}
continue;
}
ROS_WARN_STREAM("Unsupported message type" << msg.getTopic());
}
bag.close();
double runtime = (ros::WallTime::now() - start).toSec();
ROS_INFO("Bag complete, took %.1f seconds to process, shutting down", runtime);
const geometry_msgs::Quaternion & q(last_published_pose.pose.pose.orientation);
double yaw, pitch, roll;
tf2::Matrix3x3(tf2::Quaternion(q.x, q.y, q.z, q.w)).getEulerYPR(yaw,pitch,roll);
ROS_INFO("Final location %.3f, %.3f, %.3f with stamp=%f",
last_published_pose.pose.pose.position.x,
last_published_pose.pose.pose.position.y,
yaw, last_published_pose.header.stamp.toSec()
);
ros::shutdown();
}
void AmclNode::savePoseToServer()
{
// We need to apply the last transform to the latest odom pose to get
// the latest map pose to store. We'll take the covariance from
// last_published_pose.
tf2::Transform odom_pose_tf2;
tf2::convert(latest_odom_pose_.pose, odom_pose_tf2);
tf2::Transform map_pose = latest_tf_.inverse() * odom_pose_tf2;
double yaw = tf2::getYaw(map_pose.getRotation());
ROS_DEBUG("Saving pose to server. x: %.3f, y: %.3f", map_pose.getOrigin().x(), map_pose.getOrigin().y() );
private_nh_.setParam("initial_pose_x", map_pose.getOrigin().x());
private_nh_.setParam("initial_pose_y", map_pose.getOrigin().y());
private_nh_.setParam("initial_pose_a", yaw);
private_nh_.setParam("initial_cov_xx",
last_published_pose.pose.covariance[6*0+0]);
private_nh_.setParam("initial_cov_yy",
last_published_pose.pose.covariance[6*1+1]);
private_nh_.setParam("initial_cov_aa",
last_published_pose.pose.covariance[6*5+5]);
}
void AmclNode::updatePoseFromServer()
{
init_pose_[0] = 0.0;
init_pose_[1] = 0.0;
init_pose_[2] = 0.0;
init_cov_[0] = 0.5 * 0.5;
init_cov_[1] = 0.5 * 0.5;
init_cov_[2] = (M_PI/12.0) * (M_PI/12.0);
// Check for NAN on input from param server, #5239
double tmp_pos;
private_nh_.param("initial_pose_x", tmp_pos, init_pose_[0]);
if(!std::isnan(tmp_pos))
init_pose_[0] = tmp_pos;
else
ROS_WARN("ignoring NAN in initial pose X position");
private_nh_.param("initial_pose_y", tmp_pos, init_pose_[1]);
if(!std::isnan(tmp_pos))
init_pose_[1] = tmp_pos;
else
ROS_WARN("ignoring NAN in initial pose Y position");
private_nh_.param("initial_pose_a", tmp_pos, init_pose_[2]);
if(!std::isnan(tmp_pos))
init_pose_[2] = tmp_pos;
else
ROS_WARN("ignoring NAN in initial pose Yaw");
private_nh_.param("initial_cov_xx", tmp_pos, init_cov_[0]);
if(!std::isnan(tmp_pos))
init_cov_[0] =tmp_pos;
else
ROS_WARN("ignoring NAN in initial covariance XX");
private_nh_.param("initial_cov_yy", tmp_pos, init_cov_[1]);
if(!std::isnan(tmp_pos))
init_cov_[1] = tmp_pos;
else
ROS_WARN("ignoring NAN in initial covariance YY");
private_nh_.param("initial_cov_aa", tmp_pos, init_cov_[2]);
if(!std::isnan(tmp_pos))
init_cov_[2] = tmp_pos;
else
ROS_WARN("ignoring NAN in initial covariance AA");
}
void
AmclNode::checkLaserReceived(const ros::TimerEvent& event)
{
ros::Duration d = ros::Time::now() - last_laser_received_ts_;
if(d > laser_check_interval_)
{
ROS_WARN("No laser scan received (and thus no pose updates have been published) for %f seconds. Verify that data is being published on the %s topic.",
d.toSec(),
ros::names::resolve(scan_topic_).c_str());
}
}
void
AmclNode::requestMap()
{
boost::recursive_mutex::scoped_lock ml(configuration_mutex_);
// get map via RPC
nav_msgs::GetMap::Request req;
nav_msgs::GetMap::Response resp;
ROS_INFO("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
ROS_WARN("Request for map failed; trying again...");
ros::Duration d(0.5);
d.sleep();
}
handleMapMessage( resp.map );
}
void
AmclNode::mapReceived(const nav_msgs::OccupancyGridConstPtr& msg)
{
if( first_map_only_ && first_map_received_ ) {
return;
}
handleMapMessage( *msg );
first_map_received_ = true;
}
void
AmclNode::handleMapMessage(const nav_msgs::OccupancyGrid& msg)
{
boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
ROS_INFO("Received a %d X %d map @ %.3f m/pix\n",
msg.info.width,
msg.info.height,
msg.info.resolution);
if(msg.header.frame_id != global_frame_id_)
ROS_WARN("Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could cause issues with reading published topics",
msg.header.frame_id.c_str(),
global_frame_id_.c_str());
freeMapDependentMemory();
// Clear queued laser objects because they hold pointers to the existing
// map, #5202.
lasers_.clear();
lasers_update_.clear();
frame_to_laser_.clear();
map_ = convertMap(msg);
#if NEW_UNIFORM_SAMPLING
// Index of free space
free_space_indices.resize(0);
for(int i = 0; i < map_->size_x; i++)
for(int j = 0; j < map_->size_y; j++)
if(map_->cells[MAP_INDEX(map_,i,j)].occ_state == -1)
free_space_indices.push_back(std::make_pair(i,j));
#endif
// Create the particle filter
pf_ = pf_alloc(min_particles_, max_particles_,
alpha_slow_, alpha_fast_,
(pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
(void *)map_);
pf_set_selective_resampling(pf_, selective_resampling_);
pf_->pop_err = pf_err_;
pf_->pop_z = pf_z_;
// Initialize the filter
updatePoseFromServer();
pf_vector_t pf_init_pose_mean = pf_vector_zero();
pf_init_pose_mean.v[0] = init_pose_[0];
pf_init_pose_mean.v[1] = init_pose_[1];
pf_init_pose_mean.v[2] = init_pose_[2];
pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
pf_init_pose_cov.m[0][0] = init_cov_[0];
pf_init_pose_cov.m[1][1] = init_cov_[1];
pf_init_pose_cov.m[2][2] = init_cov_[2];
pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
pf_init_ = false;
// Instantiate the sensor objects
// Odometry
delete odom_;
odom_ = new AMCLOdom();
ROS_ASSERT(odom_);
odom_->SetModel( odom_model_type_, alpha1_, alpha2_, alpha3_, alpha4_, alpha5_ );
// Laser
delete laser_;
laser_ = new AMCLLaser(max_beams_, map_);
ROS_ASSERT(laser_);
if(laser_model_type_ == LASER_MODEL_BEAM)
laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_,
sigma_hit_, lambda_short_, 0.0);
else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD_PROB){
ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
laser_->SetModelLikelihoodFieldProb(z_hit_, z_rand_, sigma_hit_,
laser_likelihood_max_dist_,
do_beamskip_, beam_skip_distance_,
beam_skip_threshold_, beam_skip_error_threshold_);
ROS_INFO("Done initializing likelihood field model.");
}
else
{
ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_,
laser_likelihood_max_dist_);
ROS_INFO("Done initializing likelihood field model.");
}
// In case the initial pose message arrived before the first map,
// try to apply the initial pose now that the map has arrived.
applyInitialPose();
}
void
AmclNode::freeMapDependentMemory()
{
if( map_ != NULL ) {
map_free( map_ );
map_ = NULL;
}
if( pf_ != NULL ) {
pf_free( pf_ );
pf_ = NULL;
}
delete odom_;
odom_ = NULL;
delete laser_;
laser_ = NULL;
}
/**
* Convert an OccupancyGrid map message into the internal
* representation. This allocates a map_t and returns it.
*/
map_t*
AmclNode::convertMap( const nav_msgs::OccupancyGrid& map_msg )
{
map_t* map = map_alloc();
ROS_ASSERT(map);
map->size_x = map_msg.info.width;
map->size_y = map_msg.info.height;
map->scale = map_msg.info.resolution;
map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
// Convert to player format
map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y);
ROS_ASSERT(map->cells);