diff --git a/config/mapper_params_online_async.yaml b/config/mapper_params_online_async.yaml index ea9d93a59..288c677b1 100644 --- a/config/mapper_params_online_async.yaml +++ b/config/mapper_params_online_async.yaml @@ -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 @@ -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 \ No newline at end of file diff --git a/config/mapper_params_online_sync.yaml b/config/mapper_params_online_sync.yaml index cd4de0a94..5858cae4e 100644 --- a/config/mapper_params_online_sync.yaml +++ b/config/mapper_params_online_sync.yaml @@ -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 @@ -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 \ No newline at end of file diff --git a/include/slam_toolbox/slam_toolbox.hpp b/include/slam_toolbox/slam_toolbox.hpp index 2d896206a..b1fc180f6 100644 --- a/include/slam_toolbox/slam_toolbox.hpp +++ b/include/slam_toolbox/slam_toolbox.hpp @@ -58,6 +58,7 @@ #include #include #include +#include #include #include diff --git a/src/slam_toolbox.cpp b/src/slam_toolbox.cpp index 2df374974..f7d7f57f2 100644 --- a/src/slam_toolbox.cpp +++ b/src/slam_toolbox.cpp @@ -20,6 +20,11 @@ #include #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), @@ -467,6 +472,7 @@ void SlamToolbox::PublishGraph() /*****************************************************************************/ { std::vector graph; + boost::mutex::scoped_lock lock(mapper_mutex_); solver_->getGraph(graph); if (graph.size() == 0) @@ -1029,6 +1035,7 @@ bool SlamToolbox::SaveMapCallback(slam_toolbox::SaveMap::Request &req, /*****************************************************************************/ { std::vector graph; + boost::mutex::scoped_lock lock(mapper_mutex_); solver_->getGraph(graph); if (graph.size() == 0) { @@ -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 } @@ -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; } @@ -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;