Skip to content

Commit e0002f3

Browse files
authored
fix(costmap_generator): use vehicle frame for lidar height thresholds (#9311)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 96230fc commit e0002f3

File tree

4 files changed

+15
-10
lines changed

4 files changed

+15
-10
lines changed

planning/autoware_costmap_generator/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,8 @@ None
5050
| `grid_length_y` | int | size of gridmap for y direction |
5151
| `grid_position_x` | int | offset from coordinate in x direction |
5252
| `grid_position_y` | int | offset from coordinate in y direction |
53-
| `maximum_lidar_height_thres` | double | maximum height threshold for pointcloud data |
54-
| `minimum_lidar_height_thres` | double | minimum height threshold for pointcloud data |
53+
| `maximum_lidar_height_thres` | double | maximum height threshold for pointcloud data (relative to the vehicle_frame) |
54+
| `minimum_lidar_height_thres` | double | minimum height threshold for pointcloud data (relative to the vehicle_frame) |
5555
| `expand_rectangle_size` | double | expand object's rectangle with this value |
5656
| `size_of_expansion_kernel` | int | kernel size for blurring effect on object's costmap |
5757

planning/autoware_costmap_generator/config/costmap_generator.param.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
grid_length_y: 70.0
1313
grid_position_x: 0.0
1414
grid_position_y: 0.0
15-
maximum_lidar_height_thres: 0.3
16-
minimum_lidar_height_thres: -2.2
15+
maximum_lidar_height_thres: 2.5 # [m] when use_points is true, ignore points with a z value above this (in the vehicle_frame)
16+
minimum_lidar_height_thres: 0.0 # [m] when use_points is true, ignore points with a z value bellow this (in the vehicle_frame)
1717
use_wayarea: true
1818
use_parkinglot: true
1919
use_objects: true

planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -166,8 +166,9 @@ class CostmapGenerator : public rclcpp::Node
166166

167167
/// \brief calculate cost from pointcloud data
168168
/// \param[in] in_points: subscribed pointcloud data
169+
/// \param[in] vehicle_to_map_z: z value of the ego vehicle in the costmap frame
169170
grid_map::Matrix generatePointsCostmap(
170-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_points);
171+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_points, const double vehicle_to_map_z);
171172

172173
/// \brief calculate cost from DynamicObjectArray
173174
/// \param[in] in_objects: subscribed DynamicObjectArray

planning/autoware_costmap_generator/src/costmap_generator.cpp

+9-5
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@
5151
#include <autoware_lanelet2_extension/utility/utilities.hpp>
5252
#include <autoware_lanelet2_extension/visualization/visualization.hpp>
5353
#include <pcl_ros/transforms.hpp>
54+
#include <rclcpp/logging.hpp>
5455
#include <tf2_eigen/tf2_eigen.hpp>
5556

5657
#include <lanelet2_core/Forward.h>
@@ -303,7 +304,7 @@ void CostmapGenerator::onTimer()
303304

304305
if (param_->use_points && points_) {
305306
autoware::universe_utils::ScopedTimeTrack st("generatePointsCostmap()", *time_keeper_);
306-
costmap_[LayerName::points] = generatePointsCostmap(points_);
307+
costmap_[LayerName::points] = generatePointsCostmap(points_, tf.transform.translation.z);
307308
}
308309

309310
{
@@ -346,21 +347,24 @@ void CostmapGenerator::initGridmap()
346347
}
347348

348349
grid_map::Matrix CostmapGenerator::generatePointsCostmap(
349-
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_points)
350+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & in_points, const double vehicle_to_map_z)
350351
{
351352
geometry_msgs::msg::TransformStamped points2costmap;
352353
try {
353354
points2costmap = tf_buffer_.lookupTransform(
354355
param_->costmap_frame, in_points->header.frame_id, tf2::TimePointZero);
355356
} catch (const tf2::TransformException & ex) {
356-
RCLCPP_ERROR(rclcpp::get_logger("costmap_generator"), "%s", ex.what());
357+
RCLCPP_ERROR_THROTTLE(
358+
rclcpp::get_logger("costmap_generator"), *get_clock(), 1000, "%s", ex.what());
357359
}
358360

359361
const auto transformed_points = getTransformedPointCloud(*in_points, points2costmap.transform);
360362

363+
const auto maximum_height_thres = param_->maximum_lidar_height_thres + vehicle_to_map_z;
364+
const auto minimum_height_thres = param_->minimum_lidar_height_thres + vehicle_to_map_z;
361365
grid_map::Matrix points_costmap = points2costmap_.makeCostmapFromPoints(
362-
param_->maximum_lidar_height_thres, param_->minimum_lidar_height_thres, param_->grid_min_value,
363-
param_->grid_max_value, costmap_, LayerName::points, transformed_points);
366+
maximum_height_thres, minimum_height_thres, param_->grid_min_value, param_->grid_max_value,
367+
costmap_, LayerName::points, transformed_points);
364368

365369
return points_costmap;
366370
}

0 commit comments

Comments
 (0)