largemap_to_map.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <algorithm>
31 #include <cmath>
32 #include <map>
33 #include <string>
34 #include <vector>
35 
36 #include <ros/ros.h>
37 
38 #include <nav_msgs/OccupancyGrid.h>
41 
43 
45 {
46 private:
52 
53  nav_msgs::OccupancyGrid::ConstPtr large_map_;
56 
57  std::string robot_frame_;
58 
59  int width_;
63  std::map<size_t, std::vector<size_t>> occlusion_table_;
64 
65 public:
67  : pnh_("~")
68  , nh_()
69  , tfl_(tfbuf_)
70  {
72  pnh_.param("robot_frame", robot_frame_, std::string("base_link"));
73 
74  pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
75  nh_, "map_local",
76  pnh_, "map", 1, true);
78 
79  pnh_.param("width", width_, 30);
80  pnh_.param("round_local_map", round_local_map_, false);
81  pnh_.param("simulate_occlusion", simulate_occlusion_, false);
82  pnh_.param("simulate_surrounded", simulate_surrounded_, false);
83 
84  for (size_t addr = 0; addr < static_cast<size_t>(width_ * width_); ++addr)
85  {
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)
92  {
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;
98  occlusion_table_[addr2].push_back(addr);
99  }
100  }
101  for (auto& cell : occlusion_table_)
102  {
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);
108  }
109 
110  double hz;
111  pnh_.param("hz", hz, 1.0);
113  }
114 
115 private:
116  void cbTimer(const ros::TimerEvent& event)
117  {
118  publishMap();
119  }
120  void cbLargeMap(const nav_msgs::OccupancyGrid::ConstPtr& msg)
121  {
122  large_map_ = msg;
123  }
124  void publishMap()
125  {
126  if (!large_map_)
127  return;
129  try
130  {
131  tf2::fromMsg(tfbuf_.lookupTransform(large_map_->header.frame_id, robot_frame_, ros::Time(0)), trans);
132  }
133  catch (tf2::TransformException& e)
134  {
135  return;
136  }
137 
138  nav_msgs::OccupancyGrid map;
139  map.header.frame_id = large_map_->header.frame_id;
140  map.header.stamp = ros::Time::now();
141  map.info = large_map_->info;
142  map.info.width = width_;
143  map.info.height = width_;
144 
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;
152  map.data.resize(width_ * width_);
153 
154  const int gx =
155  std::lround((map.info.origin.position.x - large_map_->info.origin.position.x) / map.info.resolution);
156  const int gy =
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;
159 
160  for (int y = gy; y < gy + width_; ++y)
161  {
162  for (int x = gx; x < gx + width_; ++x)
163  {
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);
169  if (simulate_surrounded_ &&
170  r_sq <= std::pow(half_width, 2) &&
171  std::pow(half_width - 2, 2) <= r_sq)
172  {
173  map.data[addr] = 100;
174  }
175  else if (round_local_map_ && r_sq > std::pow(half_width, 2))
176  {
177  map.data[addr] = -1;
178  }
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))
182  {
183  map.data[addr] = -1;
184  }
185  else
186  {
187  map.data[addr] = large_map_->data[addr_large];
188  }
189  }
190  }
192  {
193  for (size_t addr = 0; addr < static_cast<size_t>(width_ * width_); ++addr)
194  {
195  if (map.data[addr] == 100)
196  {
197  for (auto a : occlusion_table_[addr])
198  {
199  map.data[a] = -1;
200  }
201  }
202  }
203  }
204 
205  pub_map_.publish(map);
206  }
207 };
208 
209 int main(int argc, char** argv)
210 {
211  ros::init(argc, argv, "largemap_to_map");
212 
213  LargeMapToMapNode conv;
214  ros::spin();
215 
216  return 0;
217 }
LargeMapToMapNode::tfbuf_
tf2_ros::Buffer tfbuf_
Definition: largemap_to_map.cpp:54
LargeMapToMapNode::robot_frame_
std::string robot_frame_
Definition: largemap_to_map.cpp:57
ros::Publisher
LargeMapToMapNode::publishMap
void publishMap()
Definition: largemap_to_map.cpp:124
LargeMapToMapNode::occlusion_table_
std::map< size_t, std::vector< size_t > > occlusion_table_
Definition: largemap_to_map.cpp:63
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
LargeMapToMapNode
Definition: largemap_to_map.cpp:44
LargeMapToMapNode::simulate_surrounded_
bool simulate_surrounded_
Definition: largemap_to_map.cpp:62
tf2::fromMsg
void fromMsg(const A &, B &b)
LargeMapToMapNode::LargeMapToMapNode
LargeMapToMapNode()
Definition: largemap_to_map.cpp:66
ros.h
LargeMapToMapNode::pub_map_
ros::Publisher pub_map_
Definition: largemap_to_map.cpp:49
tf2::Stamped
compatibility.h
LargeMapToMapNode::cbLargeMap
void cbLargeMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
Definition: largemap_to_map.cpp:120
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
LargeMapToMapNode::round_local_map_
bool round_local_map_
Definition: largemap_to_map.cpp:60
LargeMapToMapNode::cbTimer
void cbTimer(const ros::TimerEvent &event)
Definition: largemap_to_map.cpp:116
tf2_ros::TransformListener
LargeMapToMapNode::sub_largemap_
ros::Subscriber sub_largemap_
Definition: largemap_to_map.cpp:50
LargeMapToMapNode::timer_
ros::Timer timer_
Definition: largemap_to_map.cpp:51
LargeMapToMapNode::nh_
ros::NodeHandle nh_
Definition: largemap_to_map.cpp:48
tf2_ros::Buffer
LargeMapToMapNode::large_map_
nav_msgs::OccupancyGrid::ConstPtr large_map_
Definition: largemap_to_map.cpp:53
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
LargeMapToMapNode::pnh_
ros::NodeHandle pnh_
Definition: largemap_to_map.cpp:47
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
transform_listener.h
ros::Time
main
int main(int argc, char **argv)
Definition: largemap_to_map.cpp:209
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2_geometry_msgs.h
ros::spin
ROSCPP_DECL void spin()
tf2::TransformException
LargeMapToMapNode::tfl_
tf2_ros::TransformListener tfl_
Definition: largemap_to_map.cpp:55
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
LargeMapToMapNode::width_
int width_
Definition: largemap_to_map.cpp:59
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
LargeMapToMapNode::simulate_occlusion_
bool simulate_occlusion_
Definition: largemap_to_map.cpp:61
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10