wayarea2grid.h 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091
  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. */
  17. #ifndef WAYAREA_TO_GRID_H
  18. #define WAYAREA_TO_GRID_H
  19. #include <iostream>
  20. #include <vector>
  21. #include <string>
  22. #include <chrono>
  23. #include <ros/ros.h>
  24. #include <geometry_msgs/TwistStamped.h>
  25. #include <tf/transform_listener.h>
  26. #include <vector_map/vector_map.h>
  27. #include <grid_map_ros/grid_map_ros.hpp>
  28. #include <grid_map_msgs/GridMap.h>
  29. #include <grid_map_cv/grid_map_cv.hpp>
  30. #include <cv_bridge/cv_bridge.h>
  31. #include <opencv2/highgui/highgui.hpp>
  32. #include "object_map/object_map_utils.hpp"
  33. namespace object_map
  34. {
  35. class WayareaToGrid
  36. {
  37. public:
  38. WayareaToGrid();
  39. void Run();
  40. private:
  41. // handle
  42. ros::NodeHandle node_handle_;
  43. ros::NodeHandle private_node_handle_;
  44. ros::Publisher publisher_grid_map_;
  45. ros::Publisher publisher_occupancy_;
  46. grid_map::GridMap gridmap_;
  47. std::string sensor_frame_;
  48. std::string map_frame_;
  49. const std::string grid_layer_name_ = "wayarea";
  50. double grid_resolution_;
  51. double grid_length_x_;
  52. double grid_length_y_;
  53. double grid_position_x_;
  54. double grid_position_y_;
  55. double grid_position_z_;
  56. tf::TransformListener tf_listener_;
  57. int OCCUPANCY_ROAD = 128;
  58. int OCCUPANCY_NO_ROAD = 255;
  59. const int grid_min_value_ = 0;
  60. const int grid_max_value_ = 255;
  61. std::vector<std::vector<geometry_msgs::Point>> area_points_;
  62. /*!
  63. * Initializes ROS Publisher, Subscribers and sets the configuration parameters
  64. */
  65. void InitializeROSIo();
  66. };
  67. } // namespace object_map
  68. #endif // WAYAREA_TO_GRID