wayarea2grid.cpp 3.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283
  1. /*
  2. * Copyright 2018-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 "wayarea2grid.h"
  17. namespace object_map
  18. {
  19. WayareaToGrid::WayareaToGrid() :
  20. private_node_handle_("~")
  21. {
  22. InitializeROSIo();
  23. LoadRoadAreasFromVectorMap(private_node_handle_, area_points_);
  24. }
  25. void WayareaToGrid::InitializeROSIo()
  26. {
  27. private_node_handle_.param<std::string>("sensor_frame", sensor_frame_, "velodyne");
  28. private_node_handle_.param<std::string>("map_frame", map_frame_, "map");
  29. private_node_handle_.param<double>("grid_resolution", grid_resolution_, 0.2);
  30. private_node_handle_.param<double>("grid_length_x", grid_length_x_, 80);
  31. private_node_handle_.param<double>("grid_length_y", grid_length_y_, 30);
  32. private_node_handle_.param<double>("grid_position_x", grid_position_x_, 20);
  33. private_node_handle_.param<double>("grid_position_y", grid_position_y_, 0);
  34. private_node_handle_.param<double>("grid_position_z", grid_position_z_, -2.f);
  35. publisher_grid_map_ = node_handle_.advertise<grid_map_msgs::GridMap>("grid_map_wayarea", 1, true);
  36. publisher_occupancy_ = node_handle_.advertise<nav_msgs::OccupancyGrid>("occupancy_wayarea", 1, true);
  37. }
  38. void WayareaToGrid::Run()
  39. {
  40. bool set_map = false;
  41. ros::Rate loop_rate(10);
  42. while (ros::ok())
  43. {
  44. if (!set_map)
  45. {
  46. gridmap_.add(grid_layer_name_);
  47. gridmap_.setFrameId(sensor_frame_);
  48. gridmap_.setGeometry(grid_map::Length(grid_length_x_, grid_length_y_),
  49. grid_resolution_,
  50. grid_map::Position(grid_position_x_, grid_position_y_));
  51. set_map = true;
  52. }
  53. // timer start
  54. //auto start = std::chrono::system_clock::now();
  55. if (!area_points_.empty())
  56. {
  57. FillPolygonAreas(gridmap_, area_points_, grid_layer_name_, OCCUPANCY_NO_ROAD, OCCUPANCY_ROAD, grid_min_value_,
  58. grid_max_value_, sensor_frame_, map_frame_,
  59. tf_listener_);
  60. PublishGridMap(gridmap_, publisher_grid_map_);
  61. PublishOccupancyGrid(gridmap_, publisher_occupancy_, grid_layer_name_, grid_min_value_, grid_max_value_, grid_position_z_);
  62. }
  63. // timer end
  64. //auto end = std::chrono::system_clock::now();
  65. //auto usec = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count();
  66. //std::cout << "time: " << usec / 1000.0 << " [msec]" << std::endl;
  67. loop_rate.sleep();
  68. }
  69. }
  70. } // namespace object_map