Skip to content

Commit 3cf1faa

Browse files
committed
refactor(multi_object_tracker): update measureWithPose method to include InputChannel parameter and adjust related logic
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent ddb9da8 commit 3cf1faa

File tree

2 files changed

+13
-8
lines changed

2 files changed

+13
-8
lines changed

perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@ class VehicleTracker : public Tracker
5151
bool measure(
5252
const types::DynamicObject & object, const rclcpp::Time & time,
5353
const types::InputChannel & channel_info) override;
54-
bool measureWithPose(const types::DynamicObject & object);
54+
bool measureWithPose(
55+
const types::DynamicObject & object, const types::InputChannel & channel_info);
5556
bool measureWithShape(const types::DynamicObject & object);
5657
bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override;
5758
};

perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp

+11-7
Original file line numberDiff line numberDiff line change
@@ -138,11 +138,13 @@ bool VehicleTracker::predict(const rclcpp::Time & time)
138138
return motion_model_.predictState(time);
139139
}
140140

141-
bool VehicleTracker::measureWithPose(const types::DynamicObject & object)
141+
bool VehicleTracker::measureWithPose(
142+
const types::DynamicObject & object, const types::InputChannel & channel_info)
142143
{
143144
// get measurement yaw angle to update
144145
bool is_yaw_available =
145-
object.kinematics.orientation_availability != types::OrientationAvailability::UNAVAILABLE;
146+
object.kinematics.orientation_availability != types::OrientationAvailability::UNAVAILABLE &&
147+
channel_info.trust_orientation;
146148

147149
// velocity capability is checked only when the object has velocity measurement
148150
// and the predicted velocity is close to the observed velocity
@@ -198,11 +200,13 @@ bool VehicleTracker::measureWithShape(const types::DynamicObject & object)
198200
}
199201

200202
// check object size abnormality
201-
constexpr double size_max = 35.0; // [m]
202-
constexpr double size_min = 1.0; // [m]
203+
constexpr double size_max_multiplier = 1.5;
204+
constexpr double size_min_multiplier = 0.25;
203205
if (
204-
object.shape.dimensions.x > size_max || object.shape.dimensions.x < size_min ||
205-
object.shape.dimensions.y > size_max || object.shape.dimensions.y < size_min) {
206+
object.shape.dimensions.x > object_model_.size_limit.length_max * size_max_multiplier ||
207+
object.shape.dimensions.x < object_model_.size_limit.length_min * size_min_multiplier ||
208+
object.shape.dimensions.y > object_model_.size_limit.width_max * size_max_multiplier ||
209+
object.shape.dimensions.y < object_model_.size_limit.width_min * size_min_multiplier) {
206210
return false;
207211
}
208212

@@ -257,7 +261,7 @@ bool VehicleTracker::measure(
257261
// update object
258262
types::DynamicObject updating_object = in_object;
259263
shapes::calcAnchorPointOffset(object_, tracking_offset_, updating_object);
260-
measureWithPose(updating_object);
264+
measureWithPose(updating_object, channel_info);
261265
if (channel_info.trust_extension) {
262266
measureWithShape(updating_object);
263267
}

0 commit comments

Comments
 (0)