@@ -187,6 +187,15 @@ BT::NodeStatus IsDetected::tick()
187187 auto const & detection = *it;
188188 bool removed = false ;
189189
190+ if (detection.unique_id .find (" -1" ) != std::string::npos) {
191+ RCLCPP_WARN_THROTTLE (
192+ node_->get_logger (), *node_->get_clock (), 2000 ,
193+ " [IsDetected] Detection %s skipped (id is -1)" ,
194+ detection.unique_id .c_str ());
195+ it = detections.erase (it);
196+ continue ;
197+ }
198+
190199 if (detection.score > threshold_ && detection.center3d .position .z < max_depth_) {
191200 // Color filtering
192201 if (color_ != " unknown" ) {
@@ -313,7 +322,7 @@ BT::NodeStatus IsDetected::tick()
313322 bb_img_pub_->publish (*msg);
314323 }
315324
316- RCLCPP_DEBUG_THROTTLE (
325+ RCLCPP_INFO_THROTTLE (
317326 node_->get_logger (), *node_->get_clock (), 2000 ,
318327 " [IsDetected] Detections sorted" );
319328 // implement more sorting methods
@@ -323,7 +332,7 @@ BT::NodeStatus IsDetected::tick()
323332 // print pointing_direction
324333 // RCLCPP_INFO(node_->get_logger(), "Pointing direction: %d", detections[0].pointing_direction);
325334
326- RCLCPP_DEBUG_THROTTLE (
335+ RCLCPP_INFO_THROTTLE (
327336 node_->get_logger (), *node_->get_clock (), 1000 ,
328337 " [IsDetected] Detections published" );
329338 return BT::NodeStatus::SUCCESS;
0 commit comments