Skip to content

Commit 1f9486e

Browse files
tkimura4mitsudome-rnnmmnik-tier4TakaHoribe
authoredDec 4, 2021
feat: add costmap_generator package (autowarefoundation#32)
* release v0.4.0 * remove ROS1 packages temporarily Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Revert "remove ROS1 packages temporarily" This reverts commit d3dea73de174d06d8c3c97500db37501c957f521. Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * add COLCON_IGNORE to ros1 packages Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Rename launch files to launch.xml (autowarefoundation#28) * Port costmap generator (autowarefoundation#93) * ported CMakeLists.txt and package.xml to ROS2. dependency issues on grid_map_ros and grid_map_cv yet to be resolved. * working on porting changes in the code * porting in progress * porting in progress * fix subscription errors Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * porting costmap_generator from ROS1 to ROS2 completed * edited CMakeLists.txt and package.xml to fix compile and dependency errors, replaced adding external dependencies directly to adding them via rosdep. * fix parameter declarations Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * fix TFs Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * fix launch files Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * delete unnecessary files Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> Co-authored-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Convert calls of Duration to Duration::from_seconds where appropriate (autowarefoundation#131) * Rename h files to hpp (autowarefoundation#142) * Change includes * Rename files * Adjustments to make things compile * Other packages * Adjust copyright notice on 532 out of 699 source files (autowarefoundation#143) * Use quotes for includes where appropriate (autowarefoundation#144) * Use quotes for includes where appropriate * Fix lint tests * Make tests pass hopefully * Run uncrustify on the entire Pilot.Auto codebase (autowarefoundation#151) * Run uncrustify on the entire Pilot.Auto codebase * Exclude open PRs * fixing trasient_local in ROS2 packages (autowarefoundation#160) * Enable lints in costmap_generator (autowarefoundation#149) * [costmap_generator] set transient_local() option for map subscriber (autowarefoundation#217) Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * reduce terminal ouput for better error message visibility (autowarefoundation#200) * reduce terminal ouput for better error message visibility Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * [costmap_generator] fix waiting for first transform Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * fix tests Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * fix test Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Fix typos in planning modules (autowarefoundation#866) (autowarefoundation#275) * fix typos in planning * fix corresponding typos in planning * revert fixed typos temporarily due to its impact on launchers Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> * Sensor data qos (autowarefoundation#407) * Use sensor data qos for pointcloud preprocessor Signed-off-by: Autoware <autoware@tier4.jp> * Use sensor data qos for pointcloud Signed-off-by: Autoware <autoware@tier4.jp> * Fix lint Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Use sensor data qos for livox tag filter and vector map filter Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Fix lint Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> Co-authored-by: Autoware <autoware@tier4.jp> * Fix transform (autowarefoundation#420) * Replace rclcpp::Time(0) by tf2::TimePointZero() in lookupTransform Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix canTransform Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix test Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Ros2 fix topic name part1 (autowarefoundation#408) * Fix topic name of lane_departure_checker debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of mpc_follower debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of velocity_controller debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of motion_velocity_optimizer debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of lane_change_planner debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of behavior_velocity_planner debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of obstacle_avoidance_planner debug Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of behavior_velocity_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of motion_velocity_optimizer Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of lane_departure_checker Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of mpc_follower Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of behavior_velocity_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of velocity_controller Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of lane_change_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of obstacle_avoidance_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of obstacle_stop_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of costmap_generator Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of freespace_planner Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of surround_obstacle_checker Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of costmap_generator Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix topic name of emergency_handler Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix lint errors Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * Fix typo Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> * add use_sim-time option (autowarefoundation#454) * Unify Apache-2.0 license name (autowarefoundation#1242) * Refine BSD license name (autowarefoundation#1244) * Make planning modules components (autowarefoundation#1263) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Remove use_sim_time for set_parameter (autowarefoundation#1260) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Fix/fix costmap generator bugs ros2 (autowarefoundation#1358) * Fix/fix costmap generator bugs (autowarefoundation#1276) * Apply format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Transform pointcloud before generating costmap Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix makeExpandedPoint Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix lint Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Use tf2 buffer core API Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Fix wrong rate in freespace_planner (autowarefoundation#1564) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Add markdownlint and prettier (autowarefoundation#1661) * Add markdownlint and prettier Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Ignore .param.yaml Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * add sort-package-xml hook in pre-commit (autowarefoundation#1881) * add sort xml hook in pre-commit * change retval to exit_status * rename * add prettier plugin-xml * use early return * add license note * add tier4 license * restore prettier * change license order * move local hooks to public repo * move prettier-xml to pre-commit-hooks-ros * update version for bug-fix * apply pre-commit * Change formatter to clang-format and black (autowarefoundation#2332) * Revert "Temporarily comment out pre-commit hooks" This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3. * Replace ament_lint_common with autoware_lint_common Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Remove ament_cmake_uncrustify and ament_clang_format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply Black Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply clang-format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix build errors Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix for cpplint * Fix include double quotes to angle brackets Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply clang-format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix build errors Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Add COLCON_IGNORE (autowarefoundation#500) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Port parking planner packages from .Auto (autowarefoundation#600) * Copy code of 'vehicle_constants_manager' * Fix vehicle_constants_manager for ROS galactic * Rm .iv costmap_generator freespace_planner freespace_planning_aglorihtms * Add astar_search (from .Auto) * Copy freespace_planner from .Auto * Update freespace_planner for .IV * Copy costmap_generator from .Auto * Copy and update had_map_utils from .Auto * Update costmap_generator * Copy costmap_generator_nodes * Update costmap_generator_nodes * Comment out all tests * Move vehicle_constant_managers to tmp_autoware_auto_dependencies * ignore pre-commit for back-ported packages Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * ignore testing Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com> * Port parking modules (autowarefoundation#738) * Port costmap_generator * Port freespace_planner * fix readme * ci(pre-commit): autofix * fix readme Co-authored-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> Co-authored-by: Nikolai Morin <nnmmgit@gmail.com> Co-authored-by: nik-tier4 <71747268+nik-tier4@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com> Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Autoware <autoware@tier4.jp> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> Co-authored-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com> Co-authored-by: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent eb65e6f commit 1f9486e

12 files changed

+1624
-0
lines changed
 
+55
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
3+
project(costmap_generator)
4+
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 14)
7+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
8+
set(CMAKE_CXX_EXTENSIONS OFF)
9+
endif()
10+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
11+
add_compile_options(-Wall -Wextra -Wpedantic)
12+
endif()
13+
14+
find_package(ament_cmake_auto REQUIRED)
15+
find_package(PCL REQUIRED COMPONENTS common io)
16+
find_package(FLANN REQUIRED)
17+
ament_auto_find_build_dependencies()
18+
19+
include_directories(
20+
include
21+
${GRID_MAP_INCLUDE_DIR}
22+
${PCL_COMMON_INCLUDE_DIRS}
23+
${PCL_INCLUDE_DIRS}
24+
)
25+
26+
ament_auto_add_library(costmap_generator_lib SHARED
27+
nodes/costmap_generator/points_to_costmap.cpp
28+
nodes/costmap_generator/objects_to_costmap.cpp
29+
nodes/costmap_generator/object_map_utils.cpp
30+
)
31+
target_link_libraries(costmap_generator_lib
32+
${PCL_LIBRARIES}
33+
FLANN::FLANN
34+
)
35+
36+
ament_auto_add_library(costmap_generator_node SHARED
37+
nodes/costmap_generator/costmap_generator_node.cpp
38+
)
39+
target_link_libraries(costmap_generator_node
40+
${PCL_LIBRARIES}
41+
costmap_generator_lib
42+
)
43+
44+
rclcpp_components_register_node(costmap_generator_node
45+
PLUGIN "CostmapGenerator"
46+
EXECUTABLE costmap_generator
47+
)
48+
49+
if(BUILD_TESTING)
50+
find_package(ament_cmake_gtest REQUIRED)
51+
find_package(ament_lint_auto REQUIRED)
52+
ament_lint_auto_find_test_dependencies()
53+
endif()
54+
55+
ament_auto_package(INSTALL_TO_SHARE launch)

‎planning/costmap_generator/README.md

+89
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
1+
# costmap_generator
2+
3+
## costmap_generator_node
4+
5+
This node reads `PointCloud` and/or `DynamicObjectArray` and creates an `OccupancyGrid` and `GridMap`. `VectorMap(Lanelet2)` is optional.
6+
7+
### Input topics
8+
9+
| Name | Type | Description |
10+
| ------------------------- | ----------------------------------------------- | ---------------------------------------------------------------------------- |
11+
| `~input/objects` | autoware_auto_perception_msgs::PredictedObjects | predicted objects, for obstacles areas |
12+
| `~input/points_no_ground` | sensor_msgs::PointCloud2 | ground-removed points, for obstacle areas which can't be detected as objects |
13+
| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map, for drivable areas |
14+
| `~input/scenario` | autoware_planning_msgs::Scenario | scenarios to be activated, for node activation |
15+
16+
### Output topics
17+
18+
| Name | Type | Description |
19+
| ------------------------ | ----------------------- | -------------------------------------------------- |
20+
| `~output/grid_map` | grid_map_msgs::GridMap | costmap as GridMap, values are from 0.0 to 1.0 |
21+
| `~output/occupancy_grid` | nav_msgs::OccupancyGrid | costmap as OccupancyGrid, values are from 0 to 100 |
22+
23+
### Output TFs
24+
25+
None
26+
27+
### How to launch
28+
29+
1. Write your remapping info in `costmap_generator.launch` or add args when executing `roslaunch`
30+
2. Run `roslaunch costmap_generator costmap_generator.launch`
31+
32+
### Parameters
33+
34+
| Name | Type | Description |
35+
| ---------------------------- | ------ | ------------------------------------------------------- |
36+
| `update_rate` | double | timer's update rate |
37+
| `use_objects` | bool | whether using `~input/objects` or not |
38+
| `use_points` | bool | whether using `~input/points_no_ground` or not |
39+
| `use_wayarea` | bool | whether using `wayarea` from `~input/vector_map` or not |
40+
| `costmap_frame` | string | created costmap's coordinate |
41+
| `vehicle_frame` | string | vehicle's coordinate |
42+
| `map_frame` | string | map's coordinate |
43+
| `grid_min_value` | double | minimum cost for gridmap |
44+
| `grid_max_value` | double | maximum cost for gridmap |
45+
| `grid_resolution` | double | resolution for gridmap |
46+
| `grid_length_x` | int | size of gridmap for x direction |
47+
| `grid_length_y` | int | size of gridmap for y direction |
48+
| `grid_position_x` | int | offset from coordinate in x direction |
49+
| `grid_position_y` | int | offset from coordinate in y direction |
50+
| `maximum_lidar_height_thres` | double | maximum height threshold for pointcloud data |
51+
| `minimum_lidar_height_thres` | double | minimum height threshold for pointcloud data |
52+
| `expand_rectangle_size` | double | expand object's rectangle with this value |
53+
| `size_of_expansion_kernel` | int | kernel size for blurring effect on object's costmap |
54+
55+
### Flowchart
56+
57+
```plantuml
58+
@startuml
59+
title onTimer
60+
start
61+
62+
if (scenario is active?) then (yes)
63+
else (no)
64+
stop
65+
endif
66+
67+
:get current pose;
68+
69+
:set the center of costmap to current pose;
70+
71+
if (use wayarea?) then (yes)
72+
:generate wayarea costmap;
73+
endif
74+
75+
if (use objects?) then (yes)
76+
:generate objects costmap;
77+
endif
78+
79+
if (use points?) then (yes)
80+
:generate points costmap;
81+
endif
82+
83+
:combine costmap;
84+
85+
:publish costmap;
86+
87+
stop
88+
@enduml
89+
```
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,194 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright (c) 2018, Nagoya University
17+
* All rights reserved.
18+
*
19+
* Redistribution and use in source and binary forms, with or without
20+
* modification, are permitted provided that the following conditions are met:
21+
*
22+
* * Redistributions of source code must retain the above copyright notice, this
23+
* list of conditions and the following disclaimer.
24+
*
25+
* * Redistributions in binary form must reproduce the above copyright notice,
26+
* this list of conditions and the following disclaimer in the documentation
27+
* and/or other materials provided with the distribution.
28+
*
29+
* * Neither the name of Autoware nor the names of its
30+
* contributors may be used to endorse or promote products derived from
31+
* this software without specific prior written permission.
32+
*
33+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
34+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
35+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
36+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
37+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
38+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
39+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
40+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
41+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
42+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
43+
********************/
44+
45+
#ifndef COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
46+
#define COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
47+
48+
#include "costmap_generator/objects_to_costmap.hpp"
49+
#include "costmap_generator/points_to_costmap.hpp"
50+
51+
#include <grid_map_ros/GridMapRosConverter.hpp>
52+
#include <grid_map_ros/grid_map_ros.hpp>
53+
#include <lanelet2_extension/utility/message_conversion.hpp>
54+
#include <rclcpp/rclcpp.hpp>
55+
56+
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
57+
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
58+
#include <autoware_planning_msgs/msg/scenario.hpp>
59+
60+
#include <grid_map_msgs/msg/grid_map.h>
61+
#include <message_filters/subscriber.h>
62+
#include <message_filters/time_synchronizer.h>
63+
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
64+
#include <tf2_ros/buffer.h>
65+
#include <tf2_ros/transform_listener.h>
66+
67+
#include <memory>
68+
#include <string>
69+
#include <vector>
70+
71+
class CostmapGenerator : public rclcpp::Node
72+
{
73+
public:
74+
explicit CostmapGenerator(const rclcpp::NodeOptions & node_options);
75+
76+
private:
77+
bool use_objects_;
78+
bool use_points_;
79+
bool use_wayarea_;
80+
81+
lanelet::LaneletMapPtr lanelet_map_;
82+
autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_;
83+
sensor_msgs::msg::PointCloud2::ConstSharedPtr points_;
84+
85+
std::string costmap_frame_;
86+
std::string vehicle_frame_;
87+
std::string map_frame_;
88+
89+
double update_rate_;
90+
91+
double grid_min_value_;
92+
double grid_max_value_;
93+
double grid_resolution_;
94+
double grid_length_x_;
95+
double grid_length_y_;
96+
double grid_position_x_;
97+
double grid_position_y_;
98+
99+
double maximum_lidar_height_thres_;
100+
double minimum_lidar_height_thres_;
101+
102+
double expand_polygon_size_;
103+
int size_of_expansion_kernel_;
104+
105+
grid_map::GridMap costmap_;
106+
107+
rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_costmap_;
108+
rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr pub_occupancy_grid_;
109+
110+
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_points_;
111+
rclcpp::Subscription<autoware_auto_perception_msgs::msg::PredictedObjects>::SharedPtr
112+
sub_objects_;
113+
rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr sub_lanelet_bin_map_;
114+
rclcpp::Subscription<autoware_planning_msgs::msg::Scenario>::SharedPtr sub_scenario_;
115+
116+
rclcpp::TimerBase::SharedPtr timer_;
117+
118+
tf2_ros::Buffer tf_buffer_;
119+
tf2_ros::TransformListener tf_listener_;
120+
121+
std::vector<std::vector<geometry_msgs::msg::Point>> area_points_;
122+
123+
PointsToCostmap points2costmap_;
124+
ObjectsToCostmap objects2costmap_;
125+
126+
autoware_planning_msgs::msg::Scenario::ConstSharedPtr scenario_;
127+
128+
struct LayerName
129+
{
130+
static constexpr const char * objects = "objects";
131+
static constexpr const char * points = "points";
132+
static constexpr const char * wayarea = "wayarea";
133+
static constexpr const char * combined = "combined";
134+
};
135+
136+
/// \brief wait for lanelet2 map to load and build routing graph
137+
void initLaneletMap();
138+
139+
/// \brief callback for loading lanelet2 map
140+
void onLaneletMapBin(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
141+
142+
/// \brief callback for DynamicObjectArray
143+
/// \param[in] in_objects input DynamicObjectArray usually from prediction or perception
144+
/// component
145+
void onObjects(const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
146+
147+
/// \brief callback for sensor_msgs::PointCloud2
148+
/// \param[in] in_points input sensor_msgs::PointCloud2. Assuming ground-filtered pointcloud
149+
/// by default
150+
void onPoints(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
151+
152+
void onScenario(const autoware_planning_msgs::msg::Scenario::ConstSharedPtr msg);
153+
154+
void onTimer();
155+
156+
/// \brief initialize gridmap parameters based on rosparam
157+
void initGridmap();
158+
159+
/// \brief publish ros msg: grid_map::GridMap, and nav_msgs::OccupancyGrid
160+
/// \param[in] gridmap with calculated cost
161+
void publishCostmap(const grid_map::GridMap & costmap);
162+
163+
/// \brief set area_points from lanelet polygons
164+
/// \param [in] input lanelet_map
165+
/// \param [out] calculated area_points of lanelet polygons
166+
void loadRoadAreasFromLaneletMap(
167+
const lanelet::LaneletMapPtr lanelet_map,
168+
std::vector<std::vector<geometry_msgs::msg::Point>> * area_points);
169+
170+
/// \brief set area_points from parking-area polygons
171+
/// \param [in] input lanelet_map
172+
/// \param [out] calculated area_points of lanelet polygons
173+
void loadParkingAreasFromLaneletMap(
174+
const lanelet::LaneletMapPtr lanelet_map,
175+
std::vector<std::vector<geometry_msgs::msg::Point>> * area_points);
176+
177+
/// \brief calculate cost from pointcloud data
178+
/// \param[in] in_points: subscribed pointcloud data
179+
grid_map::Matrix generatePointsCostmap(
180+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_points);
181+
182+
/// \brief calculate cost from DynamicObjectArray
183+
/// \param[in] in_objects: subscribed DynamicObjectArray
184+
grid_map::Matrix generateObjectsCostmap(
185+
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr in_objects);
186+
187+
/// \brief calculate cost from lanelet2 map
188+
grid_map::Matrix generateWayAreaCostmap();
189+
190+
/// \brief calculate cost for final output
191+
grid_map::Matrix generateCombinedCostmap();
192+
};
193+
194+
#endif // COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright 2018-2019 Autoware Foundation. All rights reserved.
17+
*
18+
* Licensed under the Apache License, Version 2.0 (the "License");
19+
* you may not use this file except in compliance with the License.
20+
* You may obtain a copy of the License at
21+
*
22+
* http://www.apache.org/licenses/LICENSE-2.0
23+
*
24+
* Unless required by applicable law or agreed to in writing, software
25+
* distributed under the License is distributed on an "AS IS" BASIS,
26+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
27+
* See the License for the specific language governing permissions and
28+
* limitations under the License.
29+
********************
30+
*
31+
*/
32+
33+
#ifndef COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
34+
#define COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
35+
36+
#include <grid_map_cv/grid_map_cv.hpp>
37+
#include <grid_map_ros/grid_map_ros.hpp>
38+
#include <rclcpp/rclcpp.hpp>
39+
40+
#include <grid_map_msgs/msg/grid_map.hpp>
41+
42+
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
43+
#include <tf2_ros/buffer.h>
44+
#include <tf2_ros/transform_listener.h>
45+
46+
#include <string>
47+
#include <vector>
48+
49+
namespace object_map
50+
{
51+
/*!
52+
* Publishes in_gridmap using the specified in_publisher
53+
* @param[in] in_gridmap GridMap object to publish
54+
* @param[in] in_publisher Valid Publisher object to use
55+
*/
56+
void PublishGridMap(
57+
const grid_map::GridMap & in_gridmap,
58+
const rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr in_publisher);
59+
60+
/*!
61+
* Convert and publishes a GridMap layer to a standard Ros OccupancyGrid
62+
* @param[in] in_gridmap GridMap object to extract the layer
63+
* @param[in] in_publisher ROS Publisher to use to publish the occupancy grid
64+
* @param[in] in_layer Name of the layer to convert
65+
* @param[in] in_min_value Minimum value in the layer
66+
* @param[in] in_max_value Maximum value in the layer
67+
*/
68+
69+
void PublishOccupancyGrid(
70+
const grid_map::GridMap & in_gridmap,
71+
const rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr in_publisher,
72+
const std::string & in_layer, double in_min_value, double in_max_value, double in_height);
73+
74+
/*!
75+
* Projects the in_area_points forming the road, stores the result in out_grid_map.
76+
* @param[out] out_grid_map GridMap object to add the road grid
77+
* @param[in] in_area_points Array of points containing the wayareas
78+
* @param[in] in_grid_layer_name Name to assign to the layer
79+
* @param[in] in_layer_background_value Empty state value
80+
* @param[in] in_fill_color Value to fill on wayareas
81+
* @param[in] in_layer_min_value Minimum value in the layer
82+
* @param[in] in_layer_max_value Maximum value in the later
83+
* @param[in] in_tf_target_frame Target frame to transform the wayarea points
84+
* @param[in] in_tf_source_frame Source frame, where the points are located
85+
* @param[in] in_tf_listener Valid listener to obtain the transformation
86+
*/
87+
void FillPolygonAreas(
88+
grid_map::GridMap & out_grid_map,
89+
const std::vector<std::vector<geometry_msgs::msg::Point>> & in_area_points,
90+
const std::string & in_grid_layer_name, const int in_layer_background_value,
91+
const int in_fill_color, const int in_layer_min_value, const int in_layer_max_value,
92+
const std::string & in_tf_target_frame, const std::string & in_tf_source_frame,
93+
const tf2_ros::Buffer & in_tf_buffer);
94+
95+
} // namespace object_map
96+
97+
#endif // COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,122 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright (c) 2018, Nagoya University
17+
* All rights reserved.
18+
*
19+
* Redistribution and use in source and binary forms, with or without
20+
* modification, are permitted provided that the following conditions are met:
21+
*
22+
* * Redistributions of source code must retain the above copyright notice, this
23+
* list of conditions and the following disclaimer.
24+
*
25+
* * Redistributions in binary form must reproduce the above copyright notice,
26+
* this list of conditions and the following disclaimer in the documentation
27+
* and/or other materials provided with the distribution.
28+
*
29+
* * Neither the name of Autoware nor the names of its
30+
* contributors may be used to endorse or promote products derived from
31+
* this software without specific prior written permission.
32+
*
33+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
34+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
35+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
36+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
37+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
38+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
39+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
40+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
41+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
42+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
43+
********************/
44+
45+
#ifndef COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
46+
#define COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
47+
48+
#include <grid_map_ros/grid_map_ros.hpp>
49+
#include <rclcpp/rclcpp.hpp>
50+
51+
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
52+
53+
#include <string>
54+
55+
class ObjectsToCostmap
56+
{
57+
public:
58+
ObjectsToCostmap();
59+
60+
/// \brief calculate cost from PredictedObjects
61+
/// \param[in] costmap: initialized gridmap
62+
/// \param[in] expand_polygon_size: expand object's costmap polygon
63+
/// \param[in] size_of_expansion_kernel: kernel size for blurring cost
64+
/// \param[in] in_objects: subscribed PredictedObjects
65+
/// \param[out] calculated cost in grid_map::Matrix format
66+
grid_map::Matrix makeCostmapFromObjects(
67+
const grid_map::GridMap & costmap, const double expand_polygon_size,
68+
const double size_of_expansion_kernel,
69+
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr in_objects);
70+
71+
private:
72+
const int NUMBER_OF_POINTS;
73+
const int NUMBER_OF_DIMENSIONS;
74+
const std::string OBJECTS_COSTMAP_LAYER_;
75+
const std::string BLURRED_OBJECTS_COSTMAP_LAYER_;
76+
77+
/// \brief make 4 rectangle points from centroid position and orientation
78+
/// \param[in] in_object: subscribed one of PredictedObjects
79+
/// \param[in] expand_rectangle_size: expanding 4 points
80+
/// \param[out] 4 rectangle points
81+
Eigen::MatrixXd makeRectanglePoints(
82+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
83+
const double expand_rectangle_size);
84+
85+
/// \brief make polygon(grid_map::Polygon) from 4 rectangle's points
86+
/// \param[in] in_object: subscribed one of PredictedObjects
87+
/// \param[in] expand_rectangle_size: expanding 4 points
88+
/// \param[out] polygon with 4 rectangle points
89+
grid_map::Polygon makePolygonFromObjectBox(
90+
const std_msgs::msg::Header & header,
91+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
92+
const double expand_rectangle_size);
93+
94+
/// \brief make expanded point from convex hull's point
95+
/// \param[in] in_centroid: object's centroid
96+
/// \param[in] in_corner_point one of convex hull points
97+
/// \param[in] expand_polygon_size the param for expanding convex_hull points
98+
/// \param[out] expanded point
99+
geometry_msgs::msg::Point makeExpandedPoint(
100+
const geometry_msgs::msg::Point & in_centroid,
101+
const geometry_msgs::msg::Point32 & in_corner_point, const double expand_polygon_size);
102+
103+
/// \brief make polygon(grid_map::Polygon) from convex hull points
104+
/// \param[in] in_centroid: object's centroid
105+
/// \param[in] expand_polygon_size: expanding convex_hull points
106+
/// \param[out] polygon object with convex hull points
107+
grid_map::Polygon makePolygonFromObjectConvexHull(
108+
const std_msgs::msg::Header & header,
109+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
110+
const double expand_polygon_size);
111+
112+
/// \brief set cost in polygon by using DynamicObject's score
113+
/// \param[in] polygon: 4 rectangle points in polygon format
114+
/// \param[in] gridmap_layer_name: target gridmap layer name for calculated cost
115+
/// \param[in] score: set score as a cost for costmap
116+
/// \param[in] objects_costmap: update cost in this objects_costmap[gridmap_layer_name]
117+
void setCostInPolygon(
118+
const grid_map::Polygon & polygon, const std::string & gridmap_layer_name, const float score,
119+
grid_map::GridMap & objects_costmap);
120+
};
121+
122+
#endif // COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright (c) 2018, Nagoya University
17+
* All rights reserved.
18+
*
19+
* Redistribution and use in source and binary forms, with or without
20+
* modification, are permitted provided that the following conditions are met:
21+
*
22+
* * Redistributions of source code must retain the above copyright notice, this
23+
* list of conditions and the following disclaimer.
24+
*
25+
* * Redistributions in binary form must reproduce the above copyright notice,
26+
* this list of conditions and the following disclaimer in the documentation
27+
* and/or other materials provided with the distribution.
28+
*
29+
* * Neither the name of Autoware nor the names of its
30+
* contributors may be used to endorse or promote products derived from
31+
* this software without specific prior written permission.
32+
*
33+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
34+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
35+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
36+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
37+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
38+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
39+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
40+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
41+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
42+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
43+
********************/
44+
45+
#ifndef COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
46+
#define COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
47+
48+
#include <grid_map_ros/grid_map_ros.hpp>
49+
#include <rclcpp/rclcpp.hpp>
50+
51+
#include <pcl_conversions/pcl_conversions.h>
52+
53+
#include <string>
54+
#include <vector>
55+
56+
class PointsToCostmap
57+
{
58+
public:
59+
/// \brief calculate cost from sensor points
60+
/// \param[in] maximum_height_thres: Maximum height threshold for pointcloud data
61+
/// \param[in] minimum_height_thres: Minimum height threshold for pointcloud data
62+
/// \param[in] grid_min_value: Minimum cost for costmap
63+
/// \param[in] grid_max_value: Maximum cost fot costmap
64+
/// \param[in] gridmap: costmap based on gridmap
65+
/// \param[in] gridmap_layer_name: gridmap layer name for gridmap
66+
/// \param[in] in_sensor_points: subscribed pointcloud
67+
/// \param[out] calculated cost in grid_map::Matrix format
68+
grid_map::Matrix makeCostmapFromPoints(
69+
const double maximum_height_thres, const double minimum_height_thres,
70+
const double grid_min_value, const double grid_max_value, const grid_map::GridMap & gridmap,
71+
const std::string & gridmap_layer_name,
72+
const pcl::PointCloud<pcl::PointXYZ> & in_sensor_points);
73+
74+
private:
75+
double grid_length_x_;
76+
double grid_length_y_;
77+
double grid_resolution_;
78+
double grid_position_x_;
79+
double grid_position_y_;
80+
double y_cell_size_;
81+
double x_cell_size_;
82+
83+
/// \brief initialize gridmap parameters
84+
/// \param[in] gridmap: gridmap object to be initialized
85+
void initGridmapParam(const grid_map::GridMap & gridmap);
86+
87+
/// \brief check if index is valid in the gridmap
88+
/// \param[in] grid_ind: grid index corresponding with one of pointcloud
89+
/// \param[out] bool: true if index is valid
90+
bool isValidInd(const grid_map::Index & grid_ind);
91+
92+
/// \brief Get index from one of pointcloud
93+
/// \param[in] point: one of subscribed pointcloud
94+
/// \param[out] index in gridmap
95+
grid_map::Index fetchGridIndexFromPoint(const pcl::PointXYZ & point);
96+
97+
/// \brief Assign pointcloud to appropriate cell in gridmap
98+
/// \param[in] in_sensor_points: subscribed pointcloud
99+
/// \param[out] grid-x-length x grid-y-length size grid stuffed with point's height in
100+
/// corresponding grid cell
101+
std::vector<std::vector<std::vector<double>>> assignPoints2GridCell(
102+
const pcl::PointCloud<pcl::PointXYZ> & in_sensor_points);
103+
104+
/// \brief calculate costmap from subscribed pointcloud
105+
/// \param[in] maximum_height_thres: Maximum height threshold for pointcloud data
106+
/// \param[in] minimum_height_thres: Minimum height threshold for pointcloud data
107+
/// \param[in] grid_min_value: Minimum cost for costmap
108+
/// \param[in] grid_max_value: Maximum cost fot costmap
109+
/// \param[in] gridmap: costmap based on gridmap
110+
/// \param[in] gridmap_layer_name: gridmap layer name for gridmap
111+
/// \param[in] grid_vec: grid-x-length x grid-y-length size grid stuffed with point's height in
112+
/// corresponding grid cell \param[out] calculated costmap in grid_map::Matrix format
113+
grid_map::Matrix calculateCostmap(
114+
const double maximum_height_thres, const double minimum_lidar_height_thres,
115+
const double grid_min_value, const double grid_max_value, const grid_map::GridMap & gridmap,
116+
const std::string & gridmap_layer_name,
117+
const std::vector<std::vector<std::vector<double>>> grid_vec);
118+
};
119+
120+
#endif // COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
<launch>
2+
<arg name="input_objects" default="~/input/objects"/>
3+
<arg name="input_points_no_ground" default="~/input/points_no_ground"/>
4+
<arg name="input_lanelet_map" default="~/input/vector_map"/>
5+
<arg name="input_scenario" default="~/input/scenario"/>
6+
<arg name="output_grid_map" default="~/output/grid_map"/>
7+
<arg name="output_occupancy_grid" default="~/output/occupancy_grid"/>
8+
9+
<node pkg="costmap_generator" exec="costmap_generator" name="costmap_generator" output="screen">
10+
<remap from="~/input/objects" to="$(var input_objects)" />
11+
<remap from="~/input/points_no_ground" to="$(var input_points_no_ground)" />
12+
<remap from="~/input/vector_map" to="$(var input_lanelet_map)" />
13+
<remap from="~/input/scenario" to="$(var input_scenario)" />
14+
<remap from="~/output/grid_map" to="$(var output_grid_map)" />
15+
<remap from="~/output/occupancy_grid" to="$(var output_occupancy_grid)" />
16+
17+
<param name="costmap_frame" value="map" />
18+
<param name="vehicle_frame" value="base_link" />
19+
<param name="map_frame" value="map" />
20+
21+
<param name="update_rate" value="10.0" />
22+
23+
<param name="use_wayarea" value="true" />
24+
<param name="use_objects" value="true" />
25+
<param name="use_points" value="true" />
26+
27+
<param name="grid_min_value" value="0.0" />
28+
<param name="grid_max_value" value="1.0" />
29+
<param name="grid_resolution" value="0.2" />
30+
<param name="grid_length_x" value="70.0" />
31+
<param name="grid_length_y" value="70.0" />
32+
<param name="grid_position_x" value="0.0" />
33+
<param name="grid_position_y" value="0.0" />
34+
<param name="maximum_lidar_height_thres" value="0.3" />
35+
<param name="minimum_lidar_height_thres" value="-2.2" />
36+
<param name="expand_polygon_size" value="1.0" />
37+
<param name="size_of_expansion_kernel" value="9" />
38+
</node>
39+
</launch>

‎planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp

+407
Large diffs are not rendered by default.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,122 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright 2018-2019 Autoware Foundation. All rights reserved.
17+
*
18+
* Licensed under the Apache License, Version 2.0 (the "License");
19+
* you may not use this file except in compliance with the License.
20+
* You may obtain a copy of the License at
21+
*
22+
* http://www.apache.org/licenses/LICENSE-2.0
23+
*
24+
* Unless required by applicable law or agreed to in writing, software
25+
* distributed under the License is distributed on an "AS IS" BASIS,
26+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
27+
* See the License for the specific language governing permissions and
28+
* limitations under the License.
29+
********************
30+
*
31+
*/
32+
33+
#include "costmap_generator/object_map_utils.hpp"
34+
35+
#include <string>
36+
#include <vector>
37+
38+
namespace object_map
39+
{
40+
void PublishGridMap(
41+
const grid_map::GridMap & in_gridmap,
42+
const rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr in_publisher)
43+
{
44+
auto message = grid_map::GridMapRosConverter::toMessage(in_gridmap);
45+
in_publisher->publish(*message);
46+
}
47+
48+
void PublishOccupancyGrid(
49+
const grid_map::GridMap & in_gridmap,
50+
const rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr in_publisher,
51+
const std::string & in_layer, double in_min_value, double in_max_value, double in_height)
52+
{
53+
nav_msgs::msg::OccupancyGrid message;
54+
grid_map::GridMapRosConverter::toOccupancyGrid(
55+
in_gridmap, in_layer, in_min_value, in_max_value, message);
56+
message.info.origin.position.z = in_height;
57+
in_publisher->publish(message);
58+
}
59+
60+
void FillPolygonAreas(
61+
grid_map::GridMap & out_grid_map,
62+
const std::vector<std::vector<geometry_msgs::msg::Point>> & in_area_points,
63+
const std::string & in_grid_layer_name, const int in_layer_background_value,
64+
const int in_layer_min_value, const int in_fill_color, const int in_layer_max_value,
65+
const std::string & in_tf_target_frame, const std::string & in_tf_source_frame,
66+
const tf2_ros::Buffer & in_tf_buffer)
67+
{
68+
if (!out_grid_map.exists(in_grid_layer_name)) {
69+
out_grid_map.add(in_grid_layer_name);
70+
}
71+
out_grid_map[in_grid_layer_name].setConstant(in_layer_background_value);
72+
73+
cv::Mat original_image;
74+
grid_map::GridMapCvConverter::toImage<unsigned char, 1>(
75+
out_grid_map, in_grid_layer_name, CV_8UC1, in_layer_min_value, in_layer_max_value,
76+
original_image);
77+
78+
cv::Mat merged_filled_image = original_image.clone();
79+
80+
geometry_msgs::msg::TransformStamped transform;
81+
transform = in_tf_buffer.lookupTransform(
82+
in_tf_target_frame, in_tf_source_frame, rclcpp::Time(0), rclcpp::Duration::from_seconds(1.0));
83+
84+
// calculate out_grid_map position
85+
grid_map::Position map_pos = out_grid_map.getPosition();
86+
const double origin_x_offset = out_grid_map.getLength().x() / 2.0 - map_pos.x();
87+
const double origin_y_offset = out_grid_map.getLength().y() / 2.0 - map_pos.y();
88+
89+
for (const auto & points : in_area_points) {
90+
std::vector<cv::Point> cv_polygon;
91+
92+
for (const auto & p : points) {
93+
// transform to GridMap coordinate
94+
geometry_msgs::msg::Point transformed_point;
95+
geometry_msgs::msg::PointStamped output_stamped, input_stamped;
96+
input_stamped.point = p;
97+
tf2::doTransform(input_stamped, output_stamped, transform);
98+
transformed_point = output_stamped.point;
99+
100+
// coordinate conversion for cv image
101+
const double cv_x = (out_grid_map.getLength().y() - origin_y_offset - transformed_point.y) /
102+
out_grid_map.getResolution();
103+
const double cv_y = (out_grid_map.getLength().x() - origin_x_offset - transformed_point.x) /
104+
out_grid_map.getResolution();
105+
cv_polygon.emplace_back(cv_x, cv_y);
106+
}
107+
108+
cv::Mat filled_image = original_image.clone();
109+
110+
std::vector<std::vector<cv::Point>> cv_polygons;
111+
cv_polygons.push_back(cv_polygon);
112+
cv::fillPoly(filled_image, cv_polygons, cv::Scalar(in_fill_color));
113+
114+
merged_filled_image &= filled_image;
115+
}
116+
117+
// convert to ROS msg
118+
grid_map::GridMapCvConverter::addLayerFromImage<unsigned char, 1>(
119+
merged_filled_image, in_grid_layer_name, out_grid_map, in_layer_min_value, in_layer_max_value);
120+
}
121+
122+
} // namespace object_map
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,198 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright (c) 2018, Nagoya University
17+
* All rights reserved.
18+
*
19+
* Redistribution and use in source and binary forms, with or without
20+
* modification, are permitted provided that the following conditions are met:
21+
*
22+
* * Redistributions of source code must retain the above copyright notice, this
23+
* list of conditions and the following disclaimer.
24+
*
25+
* * Redistributions in binary form must reproduce the above copyright notice,
26+
* this list of conditions and the following disclaimer in the documentation
27+
* and/or other materials provided with the distribution.
28+
*
29+
* * Neither the name of Autoware nor the names of its
30+
* contributors may be used to endorse or promote products derived from
31+
* this software without specific prior written permission.
32+
*
33+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
34+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
35+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
36+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
37+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
38+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
39+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
40+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
41+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
42+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
43+
********************/
44+
45+
#include "costmap_generator/objects_to_costmap.hpp"
46+
47+
#include <tf2/utils.h>
48+
49+
#include <cmath>
50+
#include <string>
51+
52+
// Constructor
53+
ObjectsToCostmap::ObjectsToCostmap()
54+
: NUMBER_OF_POINTS(4),
55+
NUMBER_OF_DIMENSIONS(2),
56+
OBJECTS_COSTMAP_LAYER_("objects_costmap"),
57+
BLURRED_OBJECTS_COSTMAP_LAYER_("blurred_objects_costmap")
58+
{
59+
}
60+
61+
Eigen::MatrixXd ObjectsToCostmap::makeRectanglePoints(
62+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
63+
const double expand_rectangle_size)
64+
{
65+
double length = in_object.shape.dimensions.x + expand_rectangle_size;
66+
double width = in_object.shape.dimensions.y + expand_rectangle_size;
67+
Eigen::MatrixXd origin_points(NUMBER_OF_DIMENSIONS, NUMBER_OF_POINTS);
68+
origin_points << length / 2, length / 2, -length / 2, -length / 2, width / 2, -width / 2,
69+
-width / 2, width / 2;
70+
71+
double yaw = tf2::getYaw(in_object.kinematics.initial_pose_with_covariance.pose.orientation);
72+
Eigen::MatrixXd rotation_matrix(NUMBER_OF_DIMENSIONS, NUMBER_OF_DIMENSIONS);
73+
rotation_matrix << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw);
74+
Eigen::MatrixXd rotated_points = rotation_matrix * origin_points;
75+
76+
double dx = in_object.kinematics.initial_pose_with_covariance.pose.position.x;
77+
double dy = in_object.kinematics.initial_pose_with_covariance.pose.position.y;
78+
Eigen::MatrixXd transformed_points(NUMBER_OF_DIMENSIONS, NUMBER_OF_POINTS);
79+
Eigen::MatrixXd ones = Eigen::MatrixXd::Ones(1, NUMBER_OF_POINTS);
80+
transformed_points.row(0) = rotated_points.row(0) + dx * ones;
81+
transformed_points.row(1) = rotated_points.row(1) + dy * ones;
82+
83+
return transformed_points;
84+
}
85+
86+
grid_map::Polygon ObjectsToCostmap::makePolygonFromObjectBox(
87+
const std_msgs::msg::Header & header,
88+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
89+
const double expand_rectangle_size)
90+
{
91+
grid_map::Polygon polygon;
92+
polygon.setFrameId(header.frame_id);
93+
94+
Eigen::MatrixXd rectangle_points = makeRectanglePoints(in_object, expand_rectangle_size);
95+
for (int col = 0; col < rectangle_points.cols(); col++) {
96+
polygon.addVertex(grid_map::Position(rectangle_points(0, col), rectangle_points(1, col)));
97+
}
98+
99+
return polygon;
100+
}
101+
102+
geometry_msgs::msg::Point ObjectsToCostmap::makeExpandedPoint(
103+
const geometry_msgs::msg::Point & in_centroid,
104+
const geometry_msgs::msg::Point32 & in_corner_point, const double expand_polygon_size)
105+
{
106+
geometry_msgs::msg::Point expanded_point;
107+
108+
if (expand_polygon_size == 0) {
109+
expanded_point.x = in_corner_point.x;
110+
expanded_point.y = in_corner_point.y;
111+
return expanded_point;
112+
}
113+
114+
double theta = std::atan2(in_corner_point.y - in_centroid.y, in_corner_point.x - in_centroid.x);
115+
double delta_x = expand_polygon_size * std::cos(theta);
116+
double delta_y = expand_polygon_size * std::sin(theta);
117+
expanded_point.x = in_centroid.x + in_corner_point.x + delta_x;
118+
expanded_point.y = in_centroid.y + in_corner_point.y + delta_y;
119+
120+
return expanded_point;
121+
}
122+
123+
grid_map::Polygon ObjectsToCostmap::makePolygonFromObjectConvexHull(
124+
const std_msgs::msg::Header & header,
125+
const autoware_auto_perception_msgs::msg::PredictedObject & in_object,
126+
const double expand_polygon_size)
127+
{
128+
grid_map::Polygon polygon;
129+
polygon.setFrameId(header.frame_id);
130+
131+
double initial_z = in_object.shape.footprint.points[0].z;
132+
for (size_t index = 0; index < in_object.shape.footprint.points.size(); index++) {
133+
if (in_object.shape.footprint.points[index].z == initial_z) {
134+
geometry_msgs::msg::Point centroid =
135+
in_object.kinematics.initial_pose_with_covariance.pose.position;
136+
geometry_msgs::msg::Point expanded_point =
137+
makeExpandedPoint(centroid, in_object.shape.footprint.points[index], expand_polygon_size);
138+
polygon.addVertex(grid_map::Position(expanded_point.x, expanded_point.y));
139+
}
140+
}
141+
142+
return polygon;
143+
}
144+
145+
void ObjectsToCostmap::setCostInPolygon(
146+
const grid_map::Polygon & polygon, const std::string & gridmap_layer_name, const float score,
147+
grid_map::GridMap & objects_costmap)
148+
{
149+
for (grid_map::PolygonIterator itr(objects_costmap, polygon); !itr.isPastEnd(); ++itr) {
150+
const float current_score = objects_costmap.at(gridmap_layer_name, *itr);
151+
if (score > current_score) {
152+
objects_costmap.at(gridmap_layer_name, *itr) = score;
153+
}
154+
}
155+
}
156+
157+
grid_map::Matrix ObjectsToCostmap::makeCostmapFromObjects(
158+
const grid_map::GridMap & costmap, const double expand_polygon_size,
159+
const double size_of_expansion_kernel,
160+
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr in_objects)
161+
{
162+
grid_map::GridMap objects_costmap = costmap;
163+
objects_costmap.add(OBJECTS_COSTMAP_LAYER_, 0);
164+
objects_costmap.add(BLURRED_OBJECTS_COSTMAP_LAYER_, 0);
165+
166+
for (const auto & object : in_objects->objects) {
167+
grid_map::Polygon polygon;
168+
if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) {
169+
polygon = makePolygonFromObjectConvexHull(in_objects->header, object, expand_polygon_size);
170+
} else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {
171+
polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size);
172+
} else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) {
173+
// TODO(Kenji Miyake): Add makePolygonFromObjectCylinder
174+
polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size);
175+
}
176+
const auto highest_probability_label = *std::max_element(
177+
object.classification.begin(), object.classification.end(),
178+
[](const auto & c1, const auto & c2) { return c1.probability < c2.probability; });
179+
const double highest_probability = static_cast<double>(highest_probability_label.probability);
180+
setCostInPolygon(polygon, OBJECTS_COSTMAP_LAYER_, highest_probability, objects_costmap);
181+
setCostInPolygon(polygon, BLURRED_OBJECTS_COSTMAP_LAYER_, highest_probability, objects_costmap);
182+
}
183+
184+
// Applying mean filter to expanded gridmap
185+
const grid_map::SlidingWindowIterator::EdgeHandling edge_handling =
186+
grid_map::SlidingWindowIterator::EdgeHandling::CROP;
187+
for (grid_map::SlidingWindowIterator iterator(
188+
objects_costmap, BLURRED_OBJECTS_COSTMAP_LAYER_, edge_handling, size_of_expansion_kernel);
189+
!iterator.isPastEnd(); ++iterator) {
190+
objects_costmap.at(BLURRED_OBJECTS_COSTMAP_LAYER_, *iterator) =
191+
iterator.getData().meanOfFinites(); // Blurring.
192+
}
193+
194+
objects_costmap[OBJECTS_COSTMAP_LAYER_] = objects_costmap[OBJECTS_COSTMAP_LAYER_].cwiseMax(
195+
objects_costmap[BLURRED_OBJECTS_COSTMAP_LAYER_]);
196+
197+
return objects_costmap[OBJECTS_COSTMAP_LAYER_];
198+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,142 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/*
16+
* Copyright (c) 2018, Nagoya University
17+
* All rights reserved.
18+
*
19+
* Redistribution and use in source and binary forms, with or without
20+
* modification, are permitted provided that the following conditions are met:
21+
*
22+
* * Redistributions of source code must retain the above copyright notice, this
23+
* list of conditions and the following disclaimer.
24+
*
25+
* * Redistributions in binary form must reproduce the above copyright notice,
26+
* this list of conditions and the following disclaimer in the documentation
27+
* and/or other materials provided with the distribution.
28+
*
29+
* * Neither the name of Autoware nor the names of its
30+
* contributors may be used to endorse or promote products derived from
31+
* this software without specific prior written permission.
32+
*
33+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
34+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
35+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
36+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
37+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
38+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
39+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
40+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
41+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
42+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
43+
********************/
44+
45+
#include "costmap_generator/points_to_costmap.hpp"
46+
47+
#include <string>
48+
#include <vector>
49+
50+
void PointsToCostmap::initGridmapParam(const grid_map::GridMap & gridmap)
51+
{
52+
grid_length_x_ = gridmap.getLength().x();
53+
grid_length_y_ = gridmap.getLength().y();
54+
grid_resolution_ = gridmap.getResolution();
55+
grid_position_x_ = gridmap.getPosition().x();
56+
grid_position_y_ = gridmap.getPosition().y();
57+
}
58+
59+
bool PointsToCostmap::isValidInd(const grid_map::Index & grid_ind)
60+
{
61+
bool is_valid = false;
62+
int x_grid_ind = grid_ind.x();
63+
int y_grid_ind = grid_ind.y();
64+
if (
65+
x_grid_ind >= 0 && x_grid_ind < std::ceil(grid_length_x_ * (1 / grid_resolution_)) &&
66+
y_grid_ind >= 0 && y_grid_ind < std::ceil(grid_length_y_ * (1 / grid_resolution_))) {
67+
is_valid = true;
68+
}
69+
return is_valid;
70+
}
71+
72+
grid_map::Index PointsToCostmap::fetchGridIndexFromPoint(const pcl::PointXYZ & point)
73+
{
74+
// calculate out_grid_map position
75+
const double origin_x_offset = grid_length_x_ / 2.0 - grid_position_x_;
76+
const double origin_y_offset = grid_length_y_ / 2.0 - grid_position_y_;
77+
// coordinate conversion for making index. Set bottom left to the origin of coordinate (0, 0) in
78+
// gridmap area
79+
double mapped_x = (grid_length_x_ - origin_x_offset - point.x) / grid_resolution_;
80+
double mapped_y = (grid_length_y_ - origin_y_offset - point.y) / grid_resolution_;
81+
82+
int mapped_x_ind = std::ceil(mapped_x);
83+
int mapped_y_ind = std::ceil(mapped_y);
84+
grid_map::Index index(mapped_x_ind, mapped_y_ind);
85+
return index;
86+
}
87+
88+
std::vector<std::vector<std::vector<double>>> PointsToCostmap::assignPoints2GridCell(
89+
const pcl::PointCloud<pcl::PointXYZ> & in_sensor_points)
90+
{
91+
double y_cell_size = std::ceil(grid_length_y_ * (1 / grid_resolution_));
92+
double x_cell_size = std::ceil(grid_length_x_ * (1 / grid_resolution_));
93+
std::vector<double> z_vec;
94+
std::vector<std::vector<double>> vec_y_z(y_cell_size, z_vec);
95+
std::vector<std::vector<std::vector<double>>> vec_x_y_z(x_cell_size, vec_y_z);
96+
97+
for (const auto & point : in_sensor_points) {
98+
grid_map::Index grid_ind = fetchGridIndexFromPoint(point);
99+
if (isValidInd(grid_ind)) {
100+
vec_x_y_z[grid_ind.x()][grid_ind.y()].push_back(point.z);
101+
}
102+
}
103+
return vec_x_y_z;
104+
}
105+
106+
grid_map::Matrix PointsToCostmap::calculateCostmap(
107+
const double maximum_height_thres, const double minimum_lidar_height_thres,
108+
const double grid_min_value, const double grid_max_value, const grid_map::GridMap & gridmap,
109+
const std::string & gridmap_layer_name,
110+
const std::vector<std::vector<std::vector<double>>> grid_vec)
111+
{
112+
grid_map::Matrix gridmap_data = gridmap[gridmap_layer_name];
113+
for (size_t x_ind = 0; x_ind < grid_vec.size(); x_ind++) {
114+
for (size_t y_ind = 0; y_ind < grid_vec[0].size(); y_ind++) {
115+
if (grid_vec[x_ind][y_ind].size() == 0) {
116+
gridmap_data(x_ind, y_ind) = grid_min_value;
117+
continue;
118+
}
119+
for (const auto & z : grid_vec[x_ind][y_ind]) {
120+
if (z > maximum_height_thres || z < minimum_lidar_height_thres) {
121+
continue;
122+
}
123+
gridmap_data(x_ind, y_ind) = grid_max_value;
124+
break;
125+
}
126+
}
127+
}
128+
return gridmap_data;
129+
}
130+
131+
grid_map::Matrix PointsToCostmap::makeCostmapFromPoints(
132+
const double maximum_height_thres, const double minimum_lidar_height_thres,
133+
const double grid_min_value, const double grid_max_value, const grid_map::GridMap & gridmap,
134+
const std::string & gridmap_layer_name, const pcl::PointCloud<pcl::PointXYZ> & in_sensor_points)
135+
{
136+
initGridmapParam(gridmap);
137+
std::vector<std::vector<std::vector<double>>> grid_vec = assignPoints2GridCell(in_sensor_points);
138+
grid_map::Matrix costmap = calculateCostmap(
139+
maximum_height_thres, minimum_lidar_height_thres, grid_min_value, grid_max_value, gridmap,
140+
gridmap_layer_name, grid_vec);
141+
return costmap;
142+
}
+39
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
<?xml version="1.0"?>
2+
<package format="3">
3+
<name>costmap_generator</name>
4+
<version>0.1.0</version>
5+
<description>The costmap_generator package</description>
6+
7+
<maintainer email="kenji.miyake@tier4.jp">Kenji Miyake</maintainer>
8+
<license>Apache License 2.0</license>
9+
10+
<maintainer email="cirpue49@yahoo.co.jp">ando</maintainer>
11+
<license>BSD-3-Clause</license>
12+
13+
<buildtool_depend>ament_cmake</buildtool_depend>
14+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
15+
16+
<depend>autoware_auto_mapping_msgs</depend>
17+
<depend>autoware_auto_perception_msgs</depend>
18+
<depend>autoware_planning_msgs</depend>
19+
<depend>grid_map_ros</depend>
20+
<depend>lanelet2_extension</depend>
21+
<depend>libpcl-all-dev</depend>
22+
<depend>pcl_conversions</depend>
23+
<depend>pcl_ros</depend>
24+
<depend>rclcpp</depend>
25+
<depend>rclcpp_components</depend>
26+
<depend>tf2</depend>
27+
<depend>tf2_eigen</depend>
28+
<depend>tf2_geometry_msgs</depend>
29+
<depend>tf2_ros</depend>
30+
31+
<test_depend>ament_cmake_gtest</test_depend>
32+
<test_depend>ament_lint_auto</test_depend>
33+
<test_depend>autoware_lint_common</test_depend>
34+
35+
36+
<export>
37+
<build_type>ament_cmake</build_type>
38+
</export>
39+
</package>

0 commit comments

Comments
 (0)
Please sign in to comment.