$search
00001 /* 00002 * miniatureoccupancygrid.cc 00003 * Mac Mason <mmason@willowgarage.com> 00004 * 00005 * Implementation. See miniatureoccupancygrid.hh. 00006 */ 00007 00008 #include <cassert> 00009 #include "ros/ros.h" 00010 #include "semanticmodel/miniatureoccupancygrid.hh" 00011 00012 namespace semanticmodel 00013 { 00014 MiniatureOccupancyGrid::MiniatureOccupancyGrid(double scale) 00015 : grid(), _scale(scale), data_mutex() 00016 { 00017 } 00018 00019 boost::mutex::scoped_lock* MiniatureOccupancyGrid::get_lock() 00020 { 00021 return new boost::mutex::scoped_lock(data_mutex); 00022 } 00023 00024 // No destructor needed. 00025 00026 MiniatureOccupancyGrid::Occupancy MiniatureOccupancyGrid::get(double x, 00027 double y) const 00028 { 00029 int a, b; 00030 round_coordinates(x, y, a, b); 00031 00032 assert (x >= 0); 00033 assert (y >= 0); 00034 00035 if ((size_t) a >= grid.size()) 00036 return MiniatureOccupancyGrid::EMPTY; // Default. 00037 else if ((size_t) b >= grid.at(a).size()) 00038 return MiniatureOccupancyGrid::EMPTY; // Ditto. 00039 else 00040 return grid.at(a).at(b); 00041 } 00042 00043 void MiniatureOccupancyGrid::set(double x, double y, 00044 MiniatureOccupancyGrid::Occupancy val) 00045 { 00046 if ((x<=0) || (y<=0)) 00047 { 00048 ROS_WARN ("Received invalid coordinates to MiniatureOccupancyGrid: %f, %f", 00049 x, y); 00050 return; 00051 } 00052 00053 int a, b; 00054 round_coordinates(x, y, a, b); 00055 00056 while (grid.size() <= (size_t)a) 00057 grid.push_back(std::vector<MiniatureOccupancyGrid::Occupancy>()); 00058 00059 while (grid.at(a).size() <= (size_t)b) 00060 grid.at(a).push_back(MiniatureOccupancyGrid::EMPTY); 00061 00062 grid.at(a).at(b) = val; 00063 } 00064 00065 std::pair<size_t, size_t> MiniatureOccupancyGrid::sizes() const 00066 { 00067 size_t ysize = 0; 00068 for (size_t i = 0 ; i < grid.size() ; ++i) 00069 ysize = std::max(ysize, grid.at(i).size()); 00070 00071 return std::make_pair(grid.size(), ysize); 00072 } 00073 00074 void MiniatureOccupancyGrid::round_coordinates(double x, double y, 00075 int& a, int& b) const 00076 { 00077 // First, we need to convert x and y into grid units. 00078 double nx = x / _scale; 00079 double ny = y / _scale; 00080 00081 a = (int)nx; 00082 b = (int)ny; 00083 } 00084 00085 void MiniatureOccupancyGrid::to_msg(nav_msgs::OccupancyGrid& og) const 00086 { 00087 og.header.frame_id = "/map"; 00088 og.header.stamp = ros::Time::now(); 00089 00090 og.info.map_load_time = ros::Time::now(); 00091 og.info.resolution = _scale; 00092 std::pair<size_t, size_t> S = sizes(); 00093 og.info.height = S.second; 00094 og.info.width = S.first; 00095 og.info.origin.position.x = 00096 og.info.origin.position.y = 00097 og.info.origin.position.z = 0; 00098 og.info.origin.orientation.x = 00099 og.info.origin.orientation.y = 00100 og.info.origin.orientation.z = 0; 00101 og.info.origin.orientation.w = 1.0; 00102 00103 for (size_t j = 0 ; j < S.second ; ++j) 00104 { 00105 for (size_t i = 0 ; i < S.first ; ++i) 00106 { 00107 if (j < grid.at(i).size()) 00108 { 00109 if (grid.at(i).at(j) == OCCUPIED) 00110 og.data.push_back(100); 00111 else 00112 og.data.push_back(0); 00113 } 00114 else 00115 { 00116 og.data.push_back(0); 00117 } 00118 } 00119 } 00120 } 00121 }