38 #include <nav_msgs/OccupancyGrid.h>
74 pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
76 pnh_,
"map", 1,
true);
84 for (
size_t addr = 0; addr < static_cast<size_t>(
width_ *
width_); ++addr)
86 const int ux = addr %
width_;
87 const int uy = addr /
width_;
88 const float x = ux -
width_ / 2.0;
89 const float y = uy -
width_ / 2.0;
90 const float l = std::sqrt(x * x + y * y);
91 for (
float r = 1.0; r < l - 1.0; r += 0.5)
93 const float x2 = x * r / l;
94 const float y2 = y * r / l;
95 const int ux2 = x2 +
width_ / 2.0;
96 const int uy2 = y2 +
width_ / 2.0;
97 const int addr2 = uy2 *
width_ + ux2;
103 std::sort(cell.second.begin(), cell.second.end());
104 cell.second.erase(std::unique(cell.second.begin(), cell.second.end()), cell.second.end());
105 const auto self_it = std::find(cell.second.begin(), cell.second.end(), cell.first);
106 if (self_it != cell.second.end())
107 cell.second.erase(self_it);
120 void cbLargeMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg)
138 nav_msgs::OccupancyGrid map;
139 map.header.frame_id =
large_map_->header.frame_id;
145 const auto pos = trans.getOrigin();
146 const float x =
static_cast<int>(pos.x() / map.info.resolution) * map.info.resolution;
147 const float y =
static_cast<int>(pos.y() / map.info.resolution) * map.info.resolution;
148 map.info.origin.position.x = x - map.info.width * map.info.resolution * 0.5;
149 map.info.origin.position.y = y - map.info.height * map.info.resolution * 0.5;
150 map.info.origin.position.z = 0.0;
151 map.info.origin.orientation.w = 1.0;
155 std::lround((map.info.origin.position.x -
large_map_->info.origin.position.x) / map.info.resolution);
157 std::lround((map.info.origin.position.y -
large_map_->info.origin.position.y) / map.info.resolution);
158 const float half_width =
width_ / 2.0;
160 for (
int y = gy; y < gy +
width_; ++y)
162 for (
int x = gx; x < gx +
width_; ++x)
164 const int lx = x - gx;
165 const int ly = y - gy;
166 const size_t addr = ly *
width_ + lx;
167 const size_t addr_large = y *
large_map_->info.width + x;
168 const float r_sq = std::pow(lx - half_width, 2) + std::pow(ly - half_width, 2);
170 r_sq <= std::pow(half_width, 2) &&
171 std::pow(half_width - 2, 2) <= r_sq)
173 map.data[addr] = 100;
179 else if (x < 0 || y < 0 ||
180 x >=
static_cast<int>(
large_map_->info.width) ||
181 y >=
static_cast<int>(
large_map_->info.height))
187 map.data[addr] =
large_map_->data[addr_large];
193 for (
size_t addr = 0; addr < static_cast<size_t>(
width_ *
width_); ++addr)
195 if (map.data[addr] == 100)
209 int main(
int argc,
char** argv)
211 ros::init(argc, argv,
"largemap_to_map");