diff --git a/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp index 566887b7860ef..d7100e395ec19 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp @@ -28,10 +28,10 @@ class CarCorrector : public ShapeEstimationCorrectorInterface explicit CarCorrector(bool use_reference_yaw = false) : use_reference_yaw_(use_reference_yaw) { params_.min_width = 1.2; - params_.max_width = 2.2; + params_.max_width = 2.5; params_.avg_width = (params_.min_width + params_.max_width) * 0.5; params_.min_length = 3.0; - params_.max_length = 5.0; + params_.max_length = 5.8; params_.avg_length = (params_.min_length + params_.max_length) * 0.5; } diff --git a/perception/shape_estimation/lib/filter/car_filter.cpp b/perception/shape_estimation/lib/filter/car_filter.cpp index a40beecfc4c74..0bf911fe2deb7 100644 --- a/perception/shape_estimation/lib/filter/car_filter.cpp +++ b/perception/shape_estimation/lib/filter/car_filter.cpp @@ -19,7 +19,7 @@ bool CarFilter::filter( [[maybe_unused]] const geometry_msgs::msg::Pose & pose) { constexpr float min_width = 1.2; - constexpr float max_width = 2.2; - constexpr float max_length = 5.0; + constexpr float max_width = 2.5; + constexpr float max_length = 5.8; return utils::filterVehicleBoundingBox(shape, min_width, max_width, max_length); }