$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: dd/mm/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include <srs_env_model/but_server/plugins/map2d_plugin.h> 00029 #include <srs_env_model/topics_list.h> 00030 00031 #include <pcl_ros/transforms.h> 00032 00033 00034 srs_env_model::CMap2DPlugin::CMap2DPlugin(const std::string & name) 00035 : srs_env_model::CServerPluginBase(name) 00036 , m_publishMap2D(true) 00037 , m_map2DPublisherName(MAP2D_PUBLISHER_NAME) 00038 , m_latchedTopics(false) 00039 , m_map2DFrameId(MAP2D_FRAME_ID) 00040 , m_minSizeX(0.0) 00041 , m_minSizeY(0.0) 00042 { 00043 assert( m_data != 0 ); 00044 } 00045 00046 00047 00048 srs_env_model::CMap2DPlugin::~CMap2DPlugin() 00049 { 00050 } 00051 00052 00053 00054 bool srs_env_model::CMap2DPlugin::shouldPublish() 00055 { 00056 return( m_publishMap2D && m_map2DPublisher.getNumSubscribers() > 0 ); 00057 } 00058 00059 00060 00061 void srs_env_model::CMap2DPlugin::init(ros::NodeHandle & node_handle) 00062 { 00063 node_handle.param("collision_object_publisher", m_map2DPublisherName, MAP2D_PUBLISHER_NAME ); 00064 node_handle.param("collision_object_frame_id", m_map2DFrameId, MAP2D_FRAME_ID ); 00065 node_handle.param("min_x_size", m_minSizeX, m_minSizeX); 00066 node_handle.param("min_y_size", m_minSizeY, m_minSizeY); 00067 00068 // Create publisher 00069 m_map2DPublisher = node_handle.advertise<nav_msgs::OccupancyGrid> (m_map2DPublisherName, 5, m_latchedTopics); 00070 } 00071 00072 00073 00074 void srs_env_model::CMap2DPlugin::publishInternal(const ros::Time & timestamp) 00075 { 00076 if( shouldPublish() ) 00077 m_map2DPublisher.publish(*m_data); 00078 } 00079 00080 00081 00082 void srs_env_model::CMap2DPlugin::newMapDataCB(SMapWithParameters & par) 00083 { 00084 m_data->header.frame_id = m_map2DFrameId; 00085 m_data->header.stamp = par.currentTime; 00086 m_data->info.resolution = par.resolution; 00087 00088 m_ocFrameId = par.frameId; 00089 ros::Time timestamp( par.currentTime ); 00090 00091 tf::StampedTransform ocToMap2DTf; 00092 00093 m_bConvert = m_ocFrameId != m_map2DFrameId; 00094 00095 // Get transform 00096 try { 00097 // Transformation - to, from, time, waiting time 00098 m_tfListener.waitForTransform(m_map2DFrameId, m_ocFrameId, 00099 timestamp, ros::Duration(5)); 00100 00101 m_tfListener.lookupTransform(m_map2DFrameId, m_ocFrameId, 00102 timestamp, ocToMap2DTf); 00103 00104 } catch (tf::TransformException& ex) { 00105 ROS_ERROR_STREAM("Transform error: " << ex.what() << ", quitting callback"); 00106 PERROR( "Transform error."); 00107 return; 00108 } 00109 00110 00111 Eigen::Matrix4f ocToMap2DTM; 00112 00113 // Get transformation matrix 00114 pcl_ros::transformAsMatrix(ocToMap2DTf, ocToMap2DTM); 00115 00116 const tButServerOcMap &map(*par.map); 00117 00118 // Disassemble translation and rotation 00119 m_ocToMap2DRot = ocToMap2DTM.block<3, 3> (0, 0); 00120 m_ocToMap2DTrans = ocToMap2DTM.block<3, 1> (0, 3); 00121 00122 double minX, minY, minZ, maxX, maxY, maxZ; 00123 map.getTree().getMetricMin(minX, minY, minZ); 00124 map.getTree().getMetricMax(maxX, maxY, maxZ); 00125 00126 octomap::point3d minPt(minX, minY, minZ); 00127 octomap::point3d maxPt(maxX, maxY, maxZ); 00128 00129 octomap::OcTreeKey minKey, maxKey, curKey; 00130 00131 // Try to create key 00132 if (!map.getTree().genKey(minPt, minKey)) { 00133 ROS_ERROR("Could not create min OcTree key at %f %f %f", minPt.x(), minPt.y(), minPt.z()); 00134 return; 00135 } 00136 00137 if (!map.getTree().genKey(maxPt, maxKey)) { 00138 ROS_ERROR("Could not create max OcTree key at %f %f %f", maxPt.x(), maxPt.y(), maxPt.z()); 00139 return; 00140 } 00141 00142 ROS_DEBUG("MinKey: %d %d %d / MaxKey: %d %d %d", minKey[0], minKey[1], minKey[2], maxKey[0], maxKey[1], maxKey[2]); 00143 00144 // add padding if requested (= new min/maxPts in x&y): 00145 double halfPaddedX = 0.5 * m_minSizeX; 00146 double halfPaddedY = 0.5 * m_minSizeY; 00147 00148 minX = std::min(minX, -halfPaddedX); 00149 maxX = std::max(maxX, halfPaddedX); 00150 00151 minY = std::min(minY, -halfPaddedY); 00152 maxY = std::max(maxY, halfPaddedY); 00153 00154 minPt = octomap::point3d(minX, minY, minZ); 00155 maxPt = octomap::point3d(maxX, maxY, maxZ); 00156 00157 octomap::OcTreeKey paddedMaxKey; 00158 00159 if (!map.getTree().genKey(minPt, m_paddedMinKey)) { 00160 ROS_ERROR("Could not create padded min OcTree key at %f %f %f", minPt.x(), minPt.y(), minPt.z()); 00161 return; 00162 } 00163 00164 if (!map.getTree().genKey(maxPt, paddedMaxKey)) { 00165 ROS_ERROR("Could not create padded max OcTree key at %f %f %f", maxPt.x(), maxPt.y(), maxPt.z()); 00166 return; 00167 } 00168 00169 ROS_DEBUG("Padded MinKey: %d %d %d / padded MaxKey: %d %d %d", m_paddedMinKey[0], m_paddedMinKey[1], 00170 m_paddedMinKey[2], paddedMaxKey[0], paddedMaxKey[1], paddedMaxKey[2]); 00171 00172 assert(paddedMaxKey[0] >= maxKey[0] && paddedMaxKey[1] >= maxKey[1]); 00173 00174 m_data->info.width = paddedMaxKey[0] - m_paddedMinKey[0] + 1; 00175 m_data->info.height = paddedMaxKey[1] - m_paddedMinKey[1] + 1; 00176 00177 int mapOriginX = minKey[0] - m_paddedMinKey[0]; 00178 int mapOriginY = minKey[1] - m_paddedMinKey[1]; 00179 00180 assert(mapOriginX >= 0 && mapOriginY >= 0); 00181 00182 // might not exactly be min / max of octree: 00183 octomap::point3d origin; 00184 map.getTree().genCoords(m_paddedMinKey, par.treeDepth, origin); 00185 00186 m_data->info.origin.position.x = origin.x() - par.resolution* 0.5; 00187 m_data->info.origin.position.y = origin.y() - par.resolution * 0.5; 00188 00189 // Allocate space to hold the data (init to unknown) 00190 m_data->data.resize(m_data->info.width * m_data->info.height, -1); 00191 00192 tButServerOcTree & tree( par.map->getTree() ); 00193 srs_env_model::tButServerOcTree::leaf_iterator it, itEnd( tree.end_leafs() ); 00194 00195 // Crawl through nodes 00196 for ( it = tree.begin_leafs(m_crawlDepth); it != itEnd; ++it) 00197 { 00198 // Node is occupied? 00199 if (tree.isNodeOccupied(*it)) 00200 { 00201 handleOccupiedNode(it, par); 00202 }// Node is occupied? 00203 else 00204 { 00205 handleFreeNode( it, par ); 00206 } 00207 00208 } // Iterate through octree 00209 00210 invalidate(); 00211 } 00212 00216 void srs_env_model::CMap2DPlugin::handleOccupiedNode(srs_env_model::tButServerOcTree::iterator & it, const SMapWithParameters & mp) 00217 { 00218 if (it.getDepth() == mp.treeDepth) 00219 { 00220 00221 octomap::OcTreeKey nKey = it.getKey(); // TODO: remove intermedate obj (1.4) 00222 int i = nKey[0] - m_paddedMinKey[0]; 00223 int j = nKey[1] - m_paddedMinKey[1]; 00224 m_data->data[m_data->info.width * j + i] = 100; 00225 00226 } else { 00227 00228 int intSize = 1 << (mp.treeDepth - it.getDepth()); 00229 octomap::OcTreeKey minKey = it.getIndexKey(); 00230 for (int dx = 0; dx < intSize; dx++) { 00231 int i = minKey[0] + dx - m_paddedMinKey[0]; 00232 for (int dy = 0; dy < intSize; dy++) { 00233 int j = minKey[1] + dy - m_paddedMinKey[1]; 00234 m_data->data[m_data->info.width * j + i] = 100; 00235 } 00236 } 00237 } 00238 } 00239 00243 void srs_env_model::CMap2DPlugin::handleFreeNode(srs_env_model::tButServerOcTree::iterator & it, const SMapWithParameters & mp ) 00244 { 00245 if (it.getDepth() == mp.treeDepth) { 00246 octomap::OcTreeKey nKey = it.getKey(); //TODO: remove intermedate obj (1.4) 00247 int i = nKey[0] - m_paddedMinKey[0]; 00248 int j = nKey[1] - m_paddedMinKey[1]; 00249 if (m_data->data[m_data->info.width * j + i] == -1) { 00250 m_data->data[m_data->info.width * j + i] = 0; 00251 } 00252 } else { 00253 int intSize = 1 << (mp.treeDepth - it.getDepth()); 00254 octomap::OcTreeKey minKey = it.getIndexKey(); 00255 for (int dx = 0; dx < intSize; dx++) { 00256 int i = minKey[0] + dx - m_paddedMinKey[0]; 00257 for (int dy = 0; dy < intSize; dy++) { 00258 int j = minKey[1] + dy - m_paddedMinKey[1]; 00259 if (m_data->data[m_data->info.width * j + i] == -1) { 00260 m_data->data[m_data->info.width * j + i] = 0; 00261 } 00262 } 00263 } 00264 } 00265 } 00266 00270 void srs_env_model::CMap2DPlugin::pause( bool bPause, ros::NodeHandle & node_handle ) 00271 { 00272 if( bPause ) 00273 { 00274 m_map2DPublisher.shutdown(); 00275 } 00276 else 00277 { 00278 // Create publisher 00279 m_map2DPublisher = node_handle.advertise<nav_msgs::OccupancyGrid> (m_map2DPublisherName, 5, m_latchedTopics); 00280 } 00281 }