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
4 changes: 4 additions & 0 deletions config/mapper_params_online_async.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ ceres_loss_function: None
odom_frame: odom
map_frame: map
base_frame: base_link
laser_frame: base_laser_link
debug_logging: false
throttle_scans: 1
publish_occupancy_map: true
Expand Down Expand Up @@ -66,3 +67,6 @@ coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true

# Load Map Parameters
inverted_laser: true
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

missing laser frame?

4 changes: 4 additions & 0 deletions config/mapper_params_online_sync.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ ceres_loss_function: None
odom_frame: odom
map_frame: map
base_frame: base_link
laser_frame: base_laser_link
debug_logging: false
throttle_scans: 1
publish_occupancy_map: true
Expand Down Expand Up @@ -66,3 +67,6 @@ coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true

# Load Map Parameters
inverted_laser: true
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

missing laser frame?

1 change: 1 addition & 0 deletions include/slam_toolbox/slam_toolbox.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
#include <queue>
#include <cstdlib>
#include <fstream>
#include <sys/resource.h>

#include <boost/archive/text_oarchive.hpp>
#include <boost/archive/text_iarchive.hpp>
Expand Down
15 changes: 15 additions & 0 deletions src/slam_toolbox.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,11 @@

#include <slam_toolbox/slam_toolbox.hpp>
#include "serialization.cpp"

#define MAX_STACK_SIZE 20000000 // if a system has the stack soft limit set to a smaller value
// than needed for serialization of a large map
// parameter defines enlarged stack limit for process to use

/*****************************************************************************/
SlamToolbox::SlamToolbox() :
transform_thread_(NULL),
Expand Down Expand Up @@ -467,6 +472,7 @@ void SlamToolbox::PublishGraph()
/*****************************************************************************/
{
std::vector<Eigen::Vector2d> graph;
boost::mutex::scoped_lock lock(mapper_mutex_);
solver_->getGraph(graph);

if (graph.size() == 0)
Expand Down Expand Up @@ -1029,6 +1035,7 @@ bool SlamToolbox::SaveMapCallback(slam_toolbox::SaveMap::Request &req,
/*****************************************************************************/
{
std::vector<Eigen::Vector2d> graph;
boost::mutex::scoped_lock lock(mapper_mutex_);
solver_->getGraph(graph);
if (graph.size() == 0)
{
Expand Down Expand Up @@ -1114,6 +1121,7 @@ void SlamToolbox::Run()
scan_w_pose.scan->header.frame_id.c_str());
break;
}

AddScan(laser, scan_w_pose.scan, scan_w_pose.pose);
continue; // no need to sleep if working
}
Expand All @@ -1139,6 +1147,7 @@ bool SlamToolbox::SerializePoseGraphCallback(slam_toolbox::SerializePoseGraph::R
/*****************************************************************************/
{
const std::string filename = req.filename;
boost::mutex::scoped_lock lock(mapper_mutex_);
serialization::Write(filename, mapper_, dataset_);
return true;
}
Expand Down Expand Up @@ -1211,6 +1220,12 @@ int main(int argc, char** argv)
/*****************************************************************************/
{
ros::init(argc, argv, "slam_toolbox");
ros::NodeHandle nh;
const rlim_t max_stack_size = MAX_STACK_SIZE;
struct rlimit stack_limit;
getrlimit(RLIMIT_STACK, &stack_limit);
stack_limit.rlim_cur = max_stack_size;
setrlimit(RLIMIT_STACK, &stack_limit);
SlamToolbox kt;
ros::spin();
return 0;
Expand Down