|
44 | 44 | using Label = autoware_perception_msgs::msg::ObjectClassification;
|
45 | 45 |
|
46 | 46 | BigVehicleTracker::BigVehicleTracker(
|
47 |
| - const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, |
| 47 | + const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, |
48 | 48 | const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size,
|
49 | 49 | const uint & channel_index)
|
50 | 50 | : Tracker(time, object.classification, channel_size),
|
@@ -219,7 +219,7 @@ autoware_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatingObje
|
219 | 219 | float r_cov_x = static_cast<float>(ekf_params_.r_cov_x);
|
220 | 220 | float r_cov_y = static_cast<float>(ekf_params_.r_cov_y);
|
221 | 221 | const uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification);
|
222 |
| - if (label == autoware_auto_perception_msgs::msg::ObjectClassification::CAR) { |
| 222 | + if (label == autoware_perception_msgs::msg::ObjectClassification::CAR) { |
223 | 223 | // if label is changed, enlarge the measurement noise covariance
|
224 | 224 | constexpr float r_stddev_x = 2.0; // [m]
|
225 | 225 | constexpr float r_stddev_y = 2.0; // [m]
|
@@ -305,7 +305,7 @@ bool BigVehicleTracker::measureWithPose(
|
305 | 305 | bool BigVehicleTracker::measureWithShape(
|
306 | 306 | const autoware_perception_msgs::msg::DetectedObject & object)
|
307 | 307 | {
|
308 |
| - if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { |
| 308 | + if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { |
309 | 309 | // do not update shape if the input is not a bounding box
|
310 | 310 | return false;
|
311 | 311 | }
|
|
0 commit comments