From 320b71d6f1ef0409d65cb29b83c6235b0802843a Mon Sep 17 00:00:00 2001 From: Lisa <robbie@uni-koblenz.de> Date: Thu, 9 Feb 2017 23:04:55 +0100 Subject: [PATCH] map manager crash --- homer_map_manager/src/Managers/MaskingManager.cpp | 15 +++++++++++++++ homer_map_manager/src/map_manager_node.cpp | 6 ++---- 2 files changed, 17 insertions(+), 4 deletions(-) diff --git a/homer_map_manager/src/Managers/MaskingManager.cpp b/homer_map_manager/src/Managers/MaskingManager.cpp index 2ee1dd73..e820dc90 100644 --- a/homer_map_manager/src/Managers/MaskingManager.cpp +++ b/homer_map_manager/src/Managers/MaskingManager.cpp @@ -65,8 +65,23 @@ nav_msgs::OccupancyGrid::ConstPtr MaskingManager::modifyMap( } nav_msgs::OccupancyGrid::ConstPtr MaskingManager::resetMap() { + + + m_MaskingMap.info.width = 1; + m_MaskingMap.info.height = 1; + m_MaskingMap.info.resolution = 1; + m_MaskingMap.info.origin.position.x = 0; + m_MaskingMap.info.origin.position.y = 0; + m_MaskingMap.data.resize(m_MaskingMap.info.width * + m_MaskingMap.info.height); std::fill(m_MaskingMap.data.begin(), m_MaskingMap.data.end(), homer_mapnav_msgs::ModifyMap::NOT_MASKED); + + m_SlamMap.info = m_MaskingMap.info; + m_SlamMap.data.resize(m_SlamMap.info.width * m_SlamMap.info.height); + std::fill(m_SlamMap.data.begin(), m_SlamMap.data.end(), + homer_mapnav_msgs::ModifyMap::NOT_MASKED); + nav_msgs::OccupancyGrid::ConstPtr ret = boost::make_shared<const ::nav_msgs::OccupancyGrid>(m_MaskingMap); return ret; diff --git a/homer_map_manager/src/map_manager_node.cpp b/homer_map_manager/src/map_manager_node.cpp index 185dce9f..babc26f2 100644 --- a/homer_map_manager/src/map_manager_node.cpp +++ b/homer_map_manager/src/map_manager_node.cpp @@ -4,10 +4,8 @@ MapManagerNode::MapManagerNode(ros::NodeHandle* nh) { m_LastLaserTime = ros::Time::now(); - int mapSize; - float resolution; - ros::param::param("/homer_mapping/size", mapSize, (int)35); - ros::param::param("/homer_mapping/resolution", resolution, (float)0.05); + int mapSize = 1; + float resolution = 1; ros::param::param("/map_manager/roi_updates", m_roi_polling, (bool)false); ros::param::param("/map_manager/roi_polling_time", m_roi_polling_time, (float)0.5); -- GitLab