laserscan2costmap.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include <iostream>
  17. #include <vector>
  18. #include <string>
  19. #include <algorithm>
  20. #include <ros/ros.h>
  21. #include <sensor_msgs/LaserScan.h>
  22. #include <tf/transform_listener.h>
  23. #include <nav_msgs/OccupancyGrid.h>
  24. namespace
  25. {
  26. constexpr auto OGM_FRAME = "/map";
  27. constexpr int OCCUPIED_MAX = 8;
  28. constexpr int OCCUPIED_MIN = -8;
  29. constexpr int OCCUPIED_INCREMENT = 2;
  30. constexpr int FREE_INCREMENT = 1;
  31. std::string g_sensor_frame = "/velodyne"; // sensor which publihes lasescan message
  32. std::string g_scan_topic = "/scan"; // laser scan topic
  33. double g_resolution = 0.1; // [m]
  34. int g_scan_size_x = 1000; // actual scanning size
  35. int g_scan_size_y = 1000;
  36. int g_map_size_x = 500; // publishing occupancy grid map size
  37. int g_map_size_y = 500;
  38. struct Grid
  39. {
  40. int index;
  41. int index_x, index_y;
  42. double x, y;
  43. double weight;
  44. double range;
  45. void calcCoordinate();
  46. void calcRange();
  47. int calcGlobalIndex(const tf::StampedTransform& transform) const;
  48. };
  49. struct Cost
  50. {
  51. int occupied = 0;
  52. int free = 0;
  53. bool unknown = true;
  54. void accumulateCost(int occ, int free);
  55. };
  56. ros::Publisher g_map_pub;
  57. tf::TransformListener* g_tf_listenerp;
  58. double calcYawFromQuaternion(const tf::Quaternion& q)
  59. {
  60. tf::Matrix3x3 m(q);
  61. double roll, pitch, yaw;
  62. m.getRPY(roll, pitch, yaw);
  63. return yaw;
  64. }
  65. // Accumulate cost value
  66. void Cost::accumulateCost(int occupied_inc, int free_inc)
  67. {
  68. occupied += occupied_inc - free_inc;
  69. free += free_inc;
  70. unknown = false;
  71. if (occupied > OCCUPIED_MAX)
  72. occupied = OCCUPIED_MAX;
  73. if (occupied < OCCUPIED_MIN)
  74. occupied = OCCUPIED_MIN;
  75. }
  76. // Calcurate grid's coordinate in sensor frame
  77. void Grid::calcCoordinate()
  78. {
  79. // index coordinate
  80. index_x = index % g_scan_size_x;
  81. index_y = (index - index_x) / g_scan_size_x;
  82. // actual coordinate
  83. x = (index_x - g_scan_size_x / 2.0) * g_resolution;
  84. y = (index_y - g_scan_size_y / 2.0) * g_resolution;
  85. }
  86. // Calculate a range from sensor in a certain grid
  87. void Grid::calcRange()
  88. {
  89. double distance_x = g_resolution * fabs(g_scan_size_x / 2 - index_x);
  90. double distance_y = g_resolution * fabs(g_scan_size_y / 2 - index_y);
  91. range = sqrt(distance_x * distance_x + distance_y * distance_y);
  92. }
  93. // Change local index into global index
  94. int Grid::calcGlobalIndex(const tf::StampedTransform& transform) const
  95. {
  96. // Calculate index in global frame
  97. int ix = (x + transform.getOrigin().x()) / g_resolution;
  98. int iy = (y + transform.getOrigin().y()) / g_resolution;
  99. // Make indexes positive value
  100. int global_grid_x = (ix + 100000 * g_scan_size_x) % g_scan_size_x;
  101. int global_grid_y = (iy + 100000 * g_scan_size_y) % g_scan_size_y;
  102. int global_index = global_grid_x + global_grid_y * g_scan_size_x;
  103. return global_index;
  104. }
  105. int calcGlobalIndex(int grid_x, int grid_y, const tf::StampedTransform& transform)
  106. {
  107. // Point coordinate in velodyne(local) frame
  108. double local_x = (grid_x - g_scan_size_x / 2.0) * g_resolution;
  109. double local_y = (grid_y - g_scan_size_y / 2.0) * g_resolution;
  110. // Calculate index in global coordinate
  111. int ix = (local_x + transform.getOrigin().x()) / g_resolution;
  112. int iy = (local_y + transform.getOrigin().y()) / g_resolution;
  113. // Make indexes positive value
  114. int global_grid_x = (ix + 100000 * g_scan_size_x) % g_scan_size_x;
  115. int global_grid_y = (iy + 100000 * g_scan_size_y) % g_scan_size_y;
  116. int global_index = global_grid_x + global_grid_y * g_scan_size_x;
  117. return global_index;
  118. }
  119. void preCasting(const sensor_msgs::LaserScan& scan, std::vector<std::vector<Grid>>* precasted_grids)
  120. {
  121. int iangle_size = 2 * M_PI / scan.angle_increment;
  122. // We decide if a grid is passed by laser by this search_step
  123. double search_step = g_resolution / 10.0;
  124. // Grid indexes for each laser
  125. std::vector<std::vector<int>> grid_indexes(iangle_size);
  126. for (int iangle = 0; iangle < iangle_size; iangle++)
  127. {
  128. // Angle of each laser from Lidar
  129. double angle = scan.angle_increment * iangle; // + scan.angle_min;
  130. double step = 0;
  131. while (1)
  132. {
  133. step += search_step;
  134. // Calculate a grid index passed by laser scan
  135. int grid_x = step * cos(angle) / g_resolution + g_scan_size_x / 2.0;
  136. int grid_y = step * sin(angle) / g_resolution + g_scan_size_y / 2.0;
  137. if (grid_x >= g_scan_size_x || grid_x < 0 || grid_y >= g_scan_size_y || grid_y < 0)
  138. break;
  139. grid_indexes[iangle].push_back(grid_x + grid_y * g_scan_size_x);
  140. }
  141. }
  142. // Erase overlapping values
  143. auto unique_grid_indexes = grid_indexes;
  144. for (auto& vec : unique_grid_indexes)
  145. vec.erase(std::unique(vec.begin(), vec.end()), vec.end());
  146. // Max size of step counts
  147. // Precated laser steps for each grid are less than this value
  148. // int max_count = g_resolution / search_step * sqrt(2) + 1;
  149. for (int i = 0; i < iangle_size; i++)
  150. {
  151. // Push grid indexes for each laser
  152. // Each index has weight which is decided by passing laser rate
  153. for (const auto& unique_index : unique_grid_indexes[i])
  154. {
  155. Grid g;
  156. g.index = unique_index;
  157. // g.weight = 1.0 * std::count(grid_indexes[i].begin(), grid_indexes[i].end(), unique_index) / max_count;
  158. g.calcCoordinate();
  159. g.calcRange();
  160. precasted_grids->at(i).push_back(g);
  161. }
  162. }
  163. }
  164. // Delete old cost values
  165. void deleteOldData(std::vector<Cost>* cost_map, double current_x, double current_y, double prev_x, double prev_y)
  166. {
  167. double begin_x = current_x;
  168. double begin_y = current_y;
  169. double end_x = prev_x;
  170. double end_y = prev_y;
  171. if (begin_x > end_x)
  172. std::swap(begin_x, end_x);
  173. if (begin_y > end_y)
  174. std::swap(begin_y, end_y);
  175. int ibegin_x = begin_x / g_resolution + g_scan_size_x / 2;
  176. int ibegin_y = begin_y / g_resolution + g_scan_size_y / 2;
  177. int iend_x = end_x / g_resolution + g_scan_size_x / 2;
  178. int iend_y = end_y / g_resolution + g_scan_size_y / 2;
  179. for (int i = ibegin_x; i < iend_x; i++)
  180. {
  181. for (int j = 0; j < g_scan_size_y; j++)
  182. {
  183. int global_grid_x = (i + 100000 * g_scan_size_x) % g_scan_size_x;
  184. cost_map->at(global_grid_x + j * g_scan_size_x).occupied = 0;
  185. cost_map->at(global_grid_x + j * g_scan_size_x).free = 0;
  186. cost_map->at(global_grid_x + j * g_scan_size_x).unknown = true;
  187. }
  188. }
  189. for (int i = 0; i < g_scan_size_x; i++)
  190. {
  191. for (int j = ibegin_y; j < iend_y; j++)
  192. {
  193. int global_grid_y = (j + 100000 * g_scan_size_y) % g_scan_size_y;
  194. cost_map->at(i + global_grid_y * g_scan_size_x).occupied = 0;
  195. cost_map->at(i + global_grid_y * g_scan_size_x).free = 0;
  196. cost_map->at(i + global_grid_y * g_scan_size_x).unknown = true;
  197. }
  198. }
  199. }
  200. void setOccupancyGridMap(nav_msgs::OccupancyGrid* map, const std_msgs::Header& header,
  201. const tf::StampedTransform& transform)
  202. {
  203. map->header.stamp = header.stamp;
  204. map->header.frame_id = OGM_FRAME;
  205. map->info.map_load_time = header.stamp;
  206. map->info.resolution = g_resolution;
  207. map->info.height = g_map_size_y;
  208. map->info.width = g_map_size_x;
  209. map->info.origin.position.x = transform.getOrigin().x() - (g_map_size_x / 2) * g_resolution;
  210. map->info.origin.position.y = transform.getOrigin().y() - (g_map_size_y / 2) * g_resolution;
  211. map->info.origin.position.z = transform.getOrigin().z() - 5;
  212. map->info.origin.orientation.x = 0;
  213. map->info.origin.orientation.y = 0;
  214. map->info.origin.orientation.z = 0;
  215. map->info.origin.orientation.w = 1;
  216. }
  217. void createCostMap(const sensor_msgs::LaserScan& scan, const std::vector<std::vector<Grid>>& precasted_grids)
  218. {
  219. tf::StampedTransform transform;
  220. try
  221. {
  222. // What time should we use?
  223. g_tf_listenerp->lookupTransform(OGM_FRAME, g_sensor_frame, ros::Time(0), transform);
  224. }
  225. catch (tf::TransformException ex)
  226. {
  227. ROS_ERROR("%s", ex.what());
  228. return;
  229. }
  230. // Save costs in this variable
  231. static std::vector<Cost> cost_map(g_scan_size_x * g_scan_size_y);
  232. static bool initialized_map = false;
  233. static double prev_x = transform.getOrigin().x();
  234. static double prev_y = transform.getOrigin().y();
  235. static nav_msgs::OccupancyGrid map;
  236. setOccupancyGridMap(&map, scan.header, transform);
  237. if (!initialized_map)
  238. {
  239. map.data.resize(g_map_size_x * g_map_size_y, -1);
  240. initialized_map = true;
  241. }
  242. // Since we implement as ring buffer, we have to delete old data regularly
  243. deleteOldData(&cost_map, transform.getOrigin().x(), transform.getOrigin().y(), prev_x, prev_y);
  244. prev_x = transform.getOrigin().x();
  245. prev_y = transform.getOrigin().y();
  246. // Vehicle's orientation
  247. double yaw = calcYawFromQuaternion(transform.getRotation());
  248. // Original yaw is -PI ~ PI, so make its range 0 ~ 2PI
  249. if (yaw < 0)
  250. yaw += 2 * M_PI;
  251. static double laser_offset = fabs(scan.angle_min);
  252. // For tough_urg
  253. // static double manual_offset = -10.0 / 180 * M_PI + M_PI;
  254. // int index_offset = (yaw + laser_offset + manual_offset) / scan.angle_increment;
  255. int index_offset = (yaw + laser_offset) / scan.angle_increment;
  256. static int iangle_size = 2 * M_PI / scan.angle_increment;
  257. //----------------- RING OCCUPANCY GRID MAPPING --------------
  258. // Accumulate grid costs for each laser scan
  259. for (size_t i = 0; i < scan.ranges.size(); i++)
  260. {
  261. double range = scan.ranges[i];
  262. // Ignore 0 ranges
  263. if (range == 0)
  264. continue;
  265. // If laserscan does not reach objects, make a range max
  266. if (scan.ranges[i] > scan.range_max)
  267. range = scan.range_max;
  268. int precasted_index = (i + index_offset) % iangle_size;
  269. int obstacle_index = -1;
  270. for (const auto& g : precasted_grids[precasted_index])
  271. {
  272. obstacle_index++;
  273. if (g.range > range)
  274. break;
  275. // Free range
  276. int global_index = g.calcGlobalIndex(transform);
  277. cost_map[global_index].accumulateCost(0, FREE_INCREMENT);
  278. }
  279. // Obstacle
  280. int global_index = precasted_grids[precasted_index][obstacle_index].calcGlobalIndex(transform);
  281. cost_map[global_index].accumulateCost(OCCUPIED_INCREMENT, 0);
  282. }
  283. // Begining of grid index of publishing OGM
  284. static int origin_index_x = (g_scan_size_x - g_map_size_x) / 2.0;
  285. static int origin_index_y = (g_scan_size_y - g_map_size_y) / 2.0;
  286. // static int origin_index = origin_index_x + origin_index_y * g_scan_size_x;
  287. // Set cost values for publishing OccuppancyGridMap
  288. for (int i = 0; i < g_map_size_y; i++)
  289. {
  290. for (int j = 0; j < g_map_size_x; j++)
  291. {
  292. int scanmap_index_x = origin_index_x + j;
  293. int scanmap_index_y = origin_index_y + i;
  294. int global_index = calcGlobalIndex(scanmap_index_x, scanmap_index_y, transform);
  295. if (cost_map[global_index].unknown)
  296. map.data[j + i * g_map_size_x] = -1;
  297. else
  298. map.data[j + i * g_map_size_x] = (cost_map[global_index].occupied + 8) * 6;
  299. }
  300. }
  301. g_map_pub.publish(map);
  302. }
  303. // Make CostMap from LaserScan message
  304. void laserScanCallback(const sensor_msgs::LaserScanConstPtr& msg)
  305. {
  306. static bool precasted = false;
  307. static int iangle_size = 2 * M_PI / msg->angle_increment;
  308. static std::vector<std::vector<Grid>> precasted_grids(iangle_size);
  309. if (!precasted)
  310. {
  311. preCasting(*msg, &precasted_grids);
  312. precasted = true;
  313. }
  314. // Create costmap and publish
  315. createCostMap(*msg, precasted_grids);
  316. return;
  317. }
  318. } // namespace
  319. int main(int argc, char** argv)
  320. {
  321. ros::init(argc, argv, "laserscan2costmap");
  322. tf::TransformListener tf_listener;
  323. g_tf_listenerp = &tf_listener;
  324. ros::NodeHandle nh;
  325. ros::NodeHandle private_nh("~");
  326. private_nh.param<double>("resolution", g_resolution, 0.1);
  327. private_nh.param<int>("scan_size_x", g_scan_size_x, 1000);
  328. private_nh.param<int>("scan_size_y", g_scan_size_y, 1000);
  329. private_nh.param<int>("map_size_x", g_map_size_x, 500);
  330. private_nh.param<int>("map_size_y", g_map_size_y, 500);
  331. private_nh.param<std::string>("scan_topic", g_scan_topic, "/scan");
  332. private_nh.param<std::string>("sensor_frame", g_sensor_frame, "/velodyne");
  333. ros::Subscriber laserscan_sub = nh.subscribe(g_scan_topic, 1, laserScanCallback);
  334. g_map_pub = nh.advertise<nav_msgs::OccupancyGrid>("/ring_ogm", 1);
  335. ros::spin();
  336. return 0;
  337. }