-
Notifications
You must be signed in to change notification settings - Fork 21
/
Copy pathslam_karto_g2o.cpp
754 lines (618 loc) · 23.3 KB
/
slam_karto_g2o.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
/*
* slam_karto
* Copyright (c) 2008, Willow Garage, Inc.
*
* 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: Brian Gerkey */
/*********************************************************************
*
* Copyright (c) 2017, Saurav Agarwal
* All rights reserved.
*
*********************************************************************/
#include "ros/ros.h"
#include "ros/console.h"
#include "message_filters/subscriber.h"
#include "tf/transform_broadcaster.h"
#include "tf/transform_listener.h"
#include "tf/message_filter.h"
#include "visualization_msgs/MarkerArray.h"
#include "nav_msgs/MapMetaData.h"
#include "sensor_msgs/LaserScan.h"
#include "nav_msgs/GetMap.h"
#include "open_karto/Mapper.h"
#include "G2OSolver.h"
#include <boost/thread.hpp>
#include <string>
#include <map>
#include <vector>
// compute linear index for given map coords
#define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
class SlamKarto
{
public:
SlamKarto();
~SlamKarto();
void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan);
bool mapCallback(nav_msgs::GetMap::Request &req,
nav_msgs::GetMap::Response &res);
private:
bool getOdomPose(karto::Pose2& karto_pose, const ros::Time& t);
karto::LaserRangeFinder* getLaser(const sensor_msgs::LaserScan::ConstPtr& scan);
bool addScan(karto::LaserRangeFinder* laser,
const sensor_msgs::LaserScan::ConstPtr& scan,
karto::Pose2& karto_pose);
bool updateMap();
void publishTransform();
void publishLoop(double transform_publish_period);
void publishGraphVisualization();
// ROS handles
ros::NodeHandle node_;
tf::TransformListener tf_;
tf::TransformBroadcaster* tfB_;
message_filters::Subscriber<sensor_msgs::LaserScan>* scan_filter_sub_;
tf::MessageFilter<sensor_msgs::LaserScan>* scan_filter_;
ros::Publisher sst_;
ros::Publisher marker_publisher_;
ros::Publisher sstm_;
ros::ServiceServer ss_;
// The map that will be published / send to service callers
nav_msgs::GetMap::Response map_;
// Storage for ROS parameters
std::string odom_frame_;
std::string map_frame_;
std::string base_frame_;
int throttle_scans_;
ros::Duration map_update_interval_;
double resolution_;
boost::mutex map_mutex_;
boost::mutex map_to_odom_mutex_;
// Karto bookkeeping
karto::Mapper* mapper_;
karto::Dataset* dataset_;
G2OSolver* solver_;
std::map<std::string, karto::LaserRangeFinder*> lasers_;
std::map<std::string, bool> lasers_inverted_;
// Internal state
bool got_map_;
int laser_count_;
boost::thread* transform_thread_;
tf::Transform map_to_odom_;
unsigned marker_count_;
bool inverted_laser_;
bool use_robust_kernel_;
};
SlamKarto::SlamKarto() :
got_map_(false),
laser_count_(0),
transform_thread_(NULL),
marker_count_(0)
{
map_to_odom_.setIdentity();
// Retrieve parameters
ros::NodeHandle private_nh_("~");
if(!private_nh_.getParam("use_robust_kernel", use_robust_kernel_))
{
use_robust_kernel_ = false;
}
if(!private_nh_.getParam("odom_frame", odom_frame_))
odom_frame_ = "odom";
if(!private_nh_.getParam("map_frame", map_frame_))
map_frame_ = "map";
if(!private_nh_.getParam("base_frame", base_frame_))
base_frame_ = "base_link";
if(!private_nh_.getParam("throttle_scans", throttle_scans_))
throttle_scans_ = 1;
double tmp;
if(!private_nh_.getParam("map_update_interval", tmp))
tmp = 5.0;
map_update_interval_.fromSec(tmp);
if(!private_nh_.getParam("resolution", resolution_))
{
// Compatibility with slam_gmapping, which uses "delta" to mean
// resolution
if(!private_nh_.getParam("delta", resolution_))
resolution_ = 0.05;
}
double transform_publish_period;
private_nh_.param("transform_publish_period", transform_publish_period, 0.05);
// Set up advertisements and subscriptions
tfB_ = new tf::TransformBroadcaster();
sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
ss_ = node_.advertiseService("dynamic_map", &SlamKarto::mapCallback, this);
scan_filter_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(node_, "scan", 5);
scan_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(*scan_filter_sub_, tf_, odom_frame_, 5);
scan_filter_->registerCallback(boost::bind(&SlamKarto::laserCallback, this, _1));
marker_publisher_ = node_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array",1);
// Create a thread to periodically publish the latest map->odom
// transform; it needs to go out regularly, uninterrupted by potentially
// long periods of computation in our main loop.
transform_thread_ = new boost::thread(boost::bind(&SlamKarto::publishLoop, this, transform_publish_period));
// Initialize Karto structures
mapper_ = new karto::Mapper();
dataset_ = new karto::Dataset();
// Setting General Parameters from the Parameter Server
bool use_scan_matching = true;
if(private_nh_.getParam("use_scan_matching", use_scan_matching))
mapper_->setParamUseScanMatching(use_scan_matching);
bool use_scan_barycenter;
if(private_nh_.getParam("use_scan_barycenter", use_scan_barycenter))
mapper_->setParamUseScanBarycenter(use_scan_barycenter);
double minimum_travel_distance;
if(private_nh_.getParam("minimum_travel_distance", minimum_travel_distance))
mapper_->setParamMinimumTravelDistance(minimum_travel_distance);
double minimum_travel_heading;
if(private_nh_.getParam("minimum_travel_heading", minimum_travel_heading))
mapper_->setParamMinimumTravelHeading(minimum_travel_heading);
int scan_buffer_size;
if(private_nh_.getParam("scan_buffer_size", scan_buffer_size))
mapper_->setParamScanBufferSize(scan_buffer_size);
double scan_buffer_maximum_scan_distance;
if(private_nh_.getParam("scan_buffer_maximum_scan_distance", scan_buffer_maximum_scan_distance))
mapper_->setParamScanBufferMaximumScanDistance(scan_buffer_maximum_scan_distance);
double link_match_minimum_response_fine;
if(private_nh_.getParam("link_match_minimum_response_fine", link_match_minimum_response_fine))
mapper_->setParamLinkMatchMinimumResponseFine(link_match_minimum_response_fine);
double link_scan_maximum_distance;
if(private_nh_.getParam("link_scan_maximum_distance", link_scan_maximum_distance))
mapper_->setParamLinkScanMaximumDistance(link_scan_maximum_distance);
double loop_search_maximum_distance;
if(private_nh_.getParam("loop_search_maximum_distance", loop_search_maximum_distance))
mapper_->setParamLoopSearchMaximumDistance(loop_search_maximum_distance);
bool do_loop_closing;
if(private_nh_.getParam("do_loop_closing", do_loop_closing))
mapper_->setParamDoLoopClosing(do_loop_closing);
int loop_match_minimum_chain_size;
if(private_nh_.getParam("loop_match_minimum_chain_size", loop_match_minimum_chain_size))
mapper_->setParamLoopMatchMinimumChainSize(loop_match_minimum_chain_size);
double loop_match_maximum_variance_coarse;
if(private_nh_.getParam("loop_match_maximum_variance_coarse", loop_match_maximum_variance_coarse))
mapper_->setParamLoopMatchMaximumVarianceCoarse(loop_match_maximum_variance_coarse);
double loop_match_minimum_response_coarse;
if(private_nh_.getParam("loop_match_minimum_response_coarse", loop_match_minimum_response_coarse))
mapper_->setParamLoopMatchMinimumResponseCoarse(loop_match_minimum_response_coarse);
double loop_match_minimum_response_fine;
if(private_nh_.getParam("loop_match_minimum_response_fine", loop_match_minimum_response_fine))
mapper_->setParamLoopMatchMinimumResponseFine(loop_match_minimum_response_fine);
// Setting Correlation Parameters from the Parameter Server
double correlation_search_space_dimension;
if(private_nh_.getParam("correlation_search_space_dimension", correlation_search_space_dimension))
mapper_->setParamCorrelationSearchSpaceDimension(correlation_search_space_dimension);
double correlation_search_space_resolution;
if(private_nh_.getParam("correlation_search_space_resolution", correlation_search_space_resolution))
mapper_->setParamCorrelationSearchSpaceResolution(correlation_search_space_resolution);
double correlation_search_space_smear_deviation;
if(private_nh_.getParam("correlation_search_space_smear_deviation", correlation_search_space_smear_deviation))
mapper_->setParamCorrelationSearchSpaceSmearDeviation(correlation_search_space_smear_deviation);
// Setting Correlation Parameters, Loop Closure Parameters from the Parameter Server
double loop_search_space_dimension;
if(private_nh_.getParam("loop_search_space_dimension", loop_search_space_dimension))
mapper_->setParamLoopSearchSpaceDimension(loop_search_space_dimension);
double loop_search_space_resolution;
if(private_nh_.getParam("loop_search_space_resolution", loop_search_space_resolution))
mapper_->setParamLoopSearchSpaceResolution(loop_search_space_resolution);
double loop_search_space_smear_deviation;
if(private_nh_.getParam("loop_search_space_smear_deviation", loop_search_space_smear_deviation))
mapper_->setParamLoopSearchSpaceSmearDeviation(loop_search_space_smear_deviation);
// Setting Scan Matcher Parameters from the Parameter Server
double distance_variance_penalty;
if(private_nh_.getParam("distance_variance_penalty", distance_variance_penalty))
mapper_->setParamDistanceVariancePenalty(distance_variance_penalty);
double angle_variance_penalty;
if(private_nh_.getParam("angle_variance_penalty", angle_variance_penalty))
mapper_->setParamAngleVariancePenalty(angle_variance_penalty);
double fine_search_angle_offset;
if(private_nh_.getParam("fine_search_angle_offset", fine_search_angle_offset))
mapper_->setParamFineSearchAngleOffset(fine_search_angle_offset);
double coarse_search_angle_offset;
if(private_nh_.getParam("coarse_search_angle_offset", coarse_search_angle_offset))
mapper_->setParamCoarseSearchAngleOffset(coarse_search_angle_offset);
double coarse_angle_resolution;
if(private_nh_.getParam("coarse_angle_resolution", coarse_angle_resolution))
mapper_->setParamCoarseAngleResolution(coarse_angle_resolution);
double minimum_angle_penalty;
if(private_nh_.getParam("minimum_angle_penalty", minimum_angle_penalty))
mapper_->setParamMinimumAnglePenalty(minimum_angle_penalty);
double minimum_distance_penalty;
if(private_nh_.getParam("minimum_distance_penalty", minimum_distance_penalty))
mapper_->setParamMinimumDistancePenalty(minimum_distance_penalty);
bool use_response_expansion;
if(private_nh_.getParam("use_response_expansion", use_response_expansion))
mapper_->setParamUseResponseExpansion(use_response_expansion);
// Set solver to be used in loop closure
solver_ = new G2OSolver();
solver_->useRobustKernel(use_robust_kernel_);
mapper_->SetScanSolver(solver_);
}
SlamKarto::~SlamKarto()
{
if(transform_thread_)
{
transform_thread_->join();
delete transform_thread_;
}
if (scan_filter_)
delete scan_filter_;
if (scan_filter_sub_)
delete scan_filter_sub_;
if (solver_)
delete solver_;
if (mapper_)
delete mapper_;
if (dataset_)
delete dataset_;
// TODO: delete the pointers in the lasers_ map; not sure whether or not
// I'm supposed to do that.
}
void
SlamKarto::publishLoop(double transform_publish_period)
{
if(transform_publish_period == 0)
return;
ros::Rate r(1.0 / transform_publish_period);
while(ros::ok())
{
publishTransform();
r.sleep();
}
}
void
SlamKarto::publishTransform()
{
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
ros::Time tf_expiration = ros::Time::now() + ros::Duration(0.05);
tfB_->sendTransform(tf::StampedTransform (map_to_odom_, ros::Time::now(), map_frame_, odom_frame_));
}
karto::LaserRangeFinder*
SlamKarto::getLaser(const sensor_msgs::LaserScan::ConstPtr& scan)
{
// Check whether we know about this laser yet
if(lasers_.find(scan->header.frame_id) == lasers_.end())
{
// New laser; need to create a Karto device for it.
// Get the laser's pose, relative to base.
tf::Stamped<tf::Pose> ident;
tf::Stamped<tf::Transform> laser_pose;
ident.setIdentity();
ident.frame_id_ = scan->header.frame_id;
ident.stamp_ = scan->header.stamp;
try
{
tf_.transformPose(base_frame_, ident, laser_pose);
}
catch(tf::TransformException e)
{
ROS_WARN("Failed to compute laser pose, aborting initialization (%s)",
e.what());
return NULL;
}
double yaw = tf::getYaw(laser_pose.getRotation());
ROS_INFO("laser %s's pose wrt base: %.3f %.3f %.3f",
scan->header.frame_id.c_str(),
laser_pose.getOrigin().x(),
laser_pose.getOrigin().y(),
yaw);
// To account for lasers that are mounted upside-down,
// we create a point 1m above the laser and transform it into the laser frame
// if the point's z-value is <=0, it is upside-down
tf::Vector3 v;
v.setValue(0, 0, 1 + laser_pose.getOrigin().z());
tf::Stamped<tf::Vector3> up(v, scan->header.stamp, base_frame_);
try
{
tf_.transformPoint(scan->header.frame_id, up, up);
ROS_DEBUG("Z-Axis in sensor frame: %.3f", up.z());
}
catch (tf::TransformException& e)
{
ROS_WARN("Unable to determine orientation of laser: %s", e.what());
return NULL;
}
bool inverse = lasers_inverted_[scan->header.frame_id] = up.z() <= 0;
if (inverse)
ROS_INFO("laser is mounted upside-down");
// Create a laser range finder device and copy in data from the first
// scan
std::string name = scan->header.frame_id;
karto::LaserRangeFinder* laser =
karto::LaserRangeFinder::CreateLaserRangeFinder(karto::LaserRangeFinder_Custom, karto::Name(name));
laser->SetOffsetPose(karto::Pose2(laser_pose.getOrigin().x(),
laser_pose.getOrigin().y(),
yaw));
laser->SetMinimumRange(scan->range_min);
laser->SetMaximumRange(scan->range_max);
laser->SetMinimumAngle(scan->angle_min);
laser->SetMaximumAngle(scan->angle_max);
laser->SetAngularResolution(scan->angle_increment);
// TODO: expose this, and many other parameters
//laser_->SetRangeThreshold(12.0);
// Store this laser device for later
lasers_[scan->header.frame_id] = laser;
// Add it to the dataset, which seems to be necessary
dataset_->Add(laser);
}
return lasers_[scan->header.frame_id];
}
bool
SlamKarto::getOdomPose(karto::Pose2& karto_pose, const ros::Time& t)
{
// Get the robot's pose
tf::Stamped<tf::Pose> ident (tf::Transform(tf::createQuaternionFromRPY(0,0,0),
tf::Vector3(0,0,0)), t, base_frame_);
tf::Stamped<tf::Transform> odom_pose;
try
{
tf_.transformPose(odom_frame_, ident, odom_pose);
}
catch(tf::TransformException e)
{
ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
return false;
}
double yaw = tf::getYaw(odom_pose.getRotation());
karto_pose =
karto::Pose2(odom_pose.getOrigin().x(),
odom_pose.getOrigin().y(),
yaw);
return true;
}
void
SlamKarto::publishGraphVisualization()
{
std::vector<Eigen::Vector2d> graph_nodes;
std::vector<std::pair<Eigen::Vector2d,Eigen::Vector2d> > graph_edges;
solver_->getGraph(graph_nodes, graph_edges);
visualization_msgs::MarkerArray marray;
visualization_msgs::Marker m;
m.header.frame_id = "map";
m.header.stamp = ros::Time::now();
m.id = 0;
m.ns = "karto";
m.type = visualization_msgs::Marker::SPHERE;
m.pose.position.x = 0.0;
m.pose.position.y = 0.0;
m.pose.position.z = 0.0;
m.scale.x = 0.1;
m.scale.y = 0.1;
m.scale.z = 0.1;
m.color.r = 1.0;
m.color.g = 0;
m.color.b = 0.0;
m.color.a = 1.0;
m.lifetime = ros::Duration(0);
visualization_msgs::Marker edge;
edge.header.frame_id = "map";
edge.header.stamp = ros::Time::now();
edge.action = visualization_msgs::Marker::ADD;
edge.ns = "karto";
edge.id = 0;
edge.type = visualization_msgs::Marker::LINE_STRIP;
edge.scale.x = 0.1;
edge.scale.y = 0.1;
edge.scale.z = 0.1;
edge.color.a = 1.0;
edge.color.r = 0.0;
edge.color.g = 0.0;
edge.color.b = 1.0;
m.action = visualization_msgs::Marker::ADD;
uint id = 0;
for (uint i=0; i < graph_nodes.size(); i++)
{
m.id = id;
m.pose.position.x = graph_nodes[i](0);
m.pose.position.y = graph_nodes[i](1);
marray.markers.push_back(visualization_msgs::Marker(m));
id++;
}
for (uint i=0; i < graph_edges.size(); i++)
{
geometry_msgs::Point p;
p.x = graph_edges[i].first(0);
p.y = graph_edges[i].first(1);
edge.points.push_back(p);
p.x = graph_edges[i].second(0);
p.y = graph_edges[i].second(1);
edge.points.push_back(p);
edge.id = id;
marray.markers.push_back(visualization_msgs::Marker(edge));
id++;
}
m.action = visualization_msgs::Marker::DELETE;
for (; id < marker_count_; id++)
{
m.id = id;
marray.markers.push_back(visualization_msgs::Marker(m));
}
marker_count_ = marray.markers.size();
marker_publisher_.publish(marray);
}
void
SlamKarto::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
{
laser_count_++;
if ((laser_count_ % throttle_scans_) != 0)
return;
static ros::Time last_map_update(0,0);
// Check whether we know about this laser yet
karto::LaserRangeFinder* laser = getLaser(scan);
if(!laser)
{
ROS_WARN("Failed to create laser device for %s; discarding scan",
scan->header.frame_id.c_str());
return;
}
karto::Pose2 odom_pose;
if(addScan(laser, scan, odom_pose))
{
ROS_DEBUG("added scan at pose: %.3f %.3f %.3f",
odom_pose.GetX(),
odom_pose.GetY(),
odom_pose.GetHeading());
publishGraphVisualization();
if(!got_map_ ||
(scan->header.stamp - last_map_update) > map_update_interval_)
{
if(updateMap())
{
last_map_update = scan->header.stamp;
got_map_ = true;
ROS_DEBUG("Updated the map");
}
}
}
}
bool
SlamKarto::updateMap()
{
boost::mutex::scoped_lock lock(map_mutex_);
karto::OccupancyGrid* occ_grid =
karto::OccupancyGrid::CreateFromScans(mapper_->GetAllProcessedScans(), resolution_);
if(!occ_grid)
return false;
if(!got_map_) {
map_.map.info.resolution = resolution_;
map_.map.info.origin.position.x = 0.0;
map_.map.info.origin.position.y = 0.0;
map_.map.info.origin.position.z = 0.0;
map_.map.info.origin.orientation.x = 0.0;
map_.map.info.origin.orientation.y = 0.0;
map_.map.info.origin.orientation.z = 0.0;
map_.map.info.origin.orientation.w = 1.0;
}
// Translate to ROS format
kt_int32s width = occ_grid->GetWidth();
kt_int32s height = occ_grid->GetHeight();
karto::Vector2<kt_double> offset = occ_grid->GetCoordinateConverter()->GetOffset();
if(map_.map.info.width != (unsigned int) width ||
map_.map.info.height != (unsigned int) height ||
map_.map.info.origin.position.x != offset.GetX() ||
map_.map.info.origin.position.y != offset.GetY())
{
map_.map.info.origin.position.x = offset.GetX();
map_.map.info.origin.position.y = offset.GetY();
map_.map.info.width = width;
map_.map.info.height = height;
map_.map.data.resize(map_.map.info.width * map_.map.info.height);
}
for (kt_int32s y=0; y<height; y++)
{
for (kt_int32s x=0; x<width; x++)
{
// Getting the value at position x,y
kt_int8u value = occ_grid->GetValue(karto::Vector2<kt_int32s>(x, y));
switch (value)
{
case karto::GridStates_Unknown:
map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1;
break;
case karto::GridStates_Occupied:
map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100;
break;
case karto::GridStates_Free:
map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0;
break;
default:
ROS_WARN("Encountered unknown cell value at %d, %d", x, y);
break;
}
}
}
// Set the header information on the map
map_.map.header.stamp = ros::Time::now();
map_.map.header.frame_id = map_frame_;
sst_.publish(map_.map);
sstm_.publish(map_.map.info);
delete occ_grid;
return true;
}
bool
SlamKarto::addScan(karto::LaserRangeFinder* laser,
const sensor_msgs::LaserScan::ConstPtr& scan,
karto::Pose2& karto_pose)
{
if(!getOdomPose(karto_pose, scan->header.stamp))
return false;
// Create a vector of doubles for karto
std::vector<kt_double> readings;
if (lasers_inverted_[scan->header.frame_id]) {
for(std::vector<float>::const_reverse_iterator it = scan->ranges.rbegin();
it != scan->ranges.rend();
++it)
{
readings.push_back(*it);
}
} else {
for(std::vector<float>::const_iterator it = scan->ranges.begin();
it != scan->ranges.end();
++it)
{
readings.push_back(*it);
}
}
// create localized range scan
karto::LocalizedRangeScan* range_scan =
new karto::LocalizedRangeScan(laser->GetName(), readings);
range_scan->SetOdometricPose(karto_pose);
range_scan->SetCorrectedPose(karto_pose);
// Add the localized range scan to the mapper
bool processed;
if((processed = mapper_->Process(range_scan)))
{
//std::cout << "Pose: " << range_scan->GetOdometricPose() << " Corrected Pose: " << range_scan->GetCorrectedPose() << std::endl;
karto::Pose2 corrected_pose = range_scan->GetCorrectedPose();
// Compute the map->odom transform
tf::Stamped<tf::Pose> odom_to_map;
try
{
tf_.transformPose(odom_frame_,tf::Stamped<tf::Pose> (tf::Transform(tf::createQuaternionFromRPY(0, 0, corrected_pose.GetHeading()),
tf::Vector3(corrected_pose.GetX(), corrected_pose.GetY(), 0.0)).inverse(),
scan->header.stamp, base_frame_),odom_to_map);
}
catch(tf::TransformException e)
{
ROS_ERROR("Transform from base_link to odom failed\n");
odom_to_map.setIdentity();
}
map_to_odom_mutex_.lock();
map_to_odom_ = tf::Transform(tf::Quaternion( odom_to_map.getRotation() ),
tf::Point( odom_to_map.getOrigin() ) ).inverse();
map_to_odom_mutex_.unlock();
// Add the localized range scan to the dataset (for memory management)
dataset_->Add(range_scan);
}
else
delete range_scan;
return processed;
}
bool
SlamKarto::mapCallback(nav_msgs::GetMap::Request &req,
nav_msgs::GetMap::Response &res)
{
boost::mutex::scoped_lock lock(map_mutex_);
if(got_map_ && map_.map.info.width && map_.map.info.height)
{
res = map_;
return true;
}
else
return false;
}
int
main(int argc, char** argv)
{
ros::init(argc, argv, "slam_karto_g2o");
SlamKarto kn;
ros::spin();
return 0;
}