|
51 | 51 | #include <autoware_lanelet2_extension/utility/utilities.hpp>
|
52 | 52 | #include <autoware_lanelet2_extension/visualization/visualization.hpp>
|
53 | 53 | #include <pcl_ros/transforms.hpp>
|
| 54 | +#include <rclcpp/logging.hpp> |
54 | 55 | #include <tf2_eigen/tf2_eigen.hpp>
|
55 | 56 |
|
56 | 57 | #include <lanelet2_core/Forward.h>
|
@@ -303,7 +304,7 @@ void CostmapGenerator::onTimer()
|
303 | 304 |
|
304 | 305 | if (param_->use_points && points_) {
|
305 | 306 | autoware::universe_utils::ScopedTimeTrack st("generatePointsCostmap()", *time_keeper_);
|
306 |
| - costmap_[LayerName::points] = generatePointsCostmap(points_); |
| 307 | + costmap_[LayerName::points] = generatePointsCostmap(points_, tf.transform.translation.z); |
307 | 308 | }
|
308 | 309 |
|
309 | 310 | {
|
@@ -346,21 +347,24 @@ void CostmapGenerator::initGridmap()
|
346 | 347 | }
|
347 | 348 |
|
348 | 349 | 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) |
350 | 351 | {
|
351 | 352 | geometry_msgs::msg::TransformStamped points2costmap;
|
352 | 353 | try {
|
353 | 354 | points2costmap = tf_buffer_.lookupTransform(
|
354 | 355 | param_->costmap_frame, in_points->header.frame_id, tf2::TimePointZero);
|
355 | 356 | } 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()); |
357 | 359 | }
|
358 | 360 |
|
359 | 361 | const auto transformed_points = getTransformedPointCloud(*in_points, points2costmap.transform);
|
360 | 362 |
|
| 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; |
361 | 365 | 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); |
364 | 368 |
|
365 | 369 | return points_costmap;
|
366 | 370 | }
|
|
0 commit comments