Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion include/slam_toolbox/slam_toolbox.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ class SlamToolbox
int throttle_scans_;
ros::Duration map_update_interval_;
double resolution_, minimum_time_interval_, minimum_travel_distance_;
bool publish_occupancy_map_;
bool publish_occupancy_map_, first_measurement_;

// Karto bookkeeping
karto::Mapper* mapper_;
Expand Down
18 changes: 17 additions & 1 deletion src/slam_toolbox.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ SlamToolbox::SlamToolbox() :
pause_new_measurements_(false),
interactive_mode_(false),
laser_count_(0),
tf_(ros::Duration(14400.)) // 4 hours
tf_(ros::Duration(14400.)),
first_measurement_(true) // 4 hours
/*****************************************************************************/
{
interactive_server_ = \
Expand Down Expand Up @@ -629,6 +630,21 @@ void SlamToolbox::LaserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
return;
}

// let the first measurement pass to start the ball rolling
if (first_measurement_)
{
karto::Pose2 pose;
if(!GetOdomPose(pose, scan->header.stamp))
{
return;
}
q_.push(posed_scan(scan, pose));
last_scan_time = scan->header.stamp.toSec();
last_pose = pose;
first_measurement_ = false;
return;
}

// throttled out
laser_count_++;
if ((laser_count_ % throttle_scans_) != 0)
Expand Down