@@ -83,10 +83,18 @@ void ByteTrackNode::on_rect(
83
83
bytetrack::ObjectArray objects = bytetrack_->update_tracker (object_array);
84
84
for (const auto & tracked_object : objects) {
85
85
tier4_perception_msgs::msg::DetectedObjectWithFeature object;
86
- object.feature .roi .x_offset = tracked_object.x_offset ;
87
- object.feature .roi .y_offset = tracked_object.y_offset ;
88
- object.feature .roi .width = tracked_object.width ;
89
- object.feature .roi .height = tracked_object.height ;
86
+ // fit xy offset to 0 if roi is outside of image
87
+ const int outside_x = std::max (-tracked_object.x_offset , 0 );
88
+ const int outside_y = std::max (-tracked_object.y_offset , 0 );
89
+ const int32_t output_x = std::max (tracked_object.x_offset , 0 );
90
+ const int32_t output_y = std::max (tracked_object.y_offset , 0 );
91
+ const int32_t output_width = tracked_object.width - outside_x;
92
+ const int32_t output_height = tracked_object.height - outside_y;
93
+ // convert int32 to uint32
94
+ object.feature .roi .x_offset = static_cast <uint32_t >(output_x);
95
+ object.feature .roi .y_offset = static_cast <uint32_t >(output_y);
96
+ object.feature .roi .width = static_cast <uint32_t >(output_width);
97
+ object.feature .roi .height = static_cast <uint32_t >(output_height);
90
98
object.object .existence_probability = tracked_object.score ;
91
99
object.object .classification .emplace_back (
92
100
autoware_auto_perception_msgs::build<Label>().label (tracked_object.type ).probability (1 .0f ));
0 commit comments