Skip to content

Commit

Permalink
add missing fields, remove deprecated definitions (#574)
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam authored Aug 14, 2024
1 parent 82ce67c commit 090a291
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 22 deletions.
12 changes: 1 addition & 11 deletions depthai_bridge/src/ImgDetectionConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,21 +61,11 @@ void ImgDetectionConverter::toRosMsg(std::shared_ptr<dai::ImgDetections> inNetDa

opDetectionMsg.detections[i].results.resize(1);

#if defined(IS_GALACTIC) || defined(IS_HUMBLE)
opDetectionMsg.detections[i].id = std::to_string(inNetData->detections[i].label);
opDetectionMsg.detections[i].results[0].hypothesis.class_id = std::to_string(inNetData->detections[i].label);
opDetectionMsg.detections[i].results[0].hypothesis.score = inNetData->detections[i].confidence;
#elif IS_ROS2
opDetectionMsg.detections[i].results[0].id = std::to_string(inNetData->detections[i].label);
opDetectionMsg.detections[i].results[0].score = inNetData->detections[i].confidence;
#endif
#ifdef IS_HUMBLE
opDetectionMsg.detections[i].bbox.center.position.x = xCenter;
opDetectionMsg.detections[i].bbox.center.position.y = yCenter;
#else
opDetectionMsg.detections[i].bbox.center.x = xCenter;
opDetectionMsg.detections[i].bbox.center.y = yCenter;
#endif
opDetectionMsg.detections[i].bbox.size_x = xSize;
opDetectionMsg.detections[i].bbox.size_y = ySize;
}
Expand All @@ -96,4 +86,4 @@ Detection2DArrayPtr ImgDetectionConverter::toRosMsgPtr(std::shared_ptr<dai::ImgD
}

} // namespace ros
} // namespace dai
} // namespace dai
14 changes: 3 additions & 11 deletions depthai_bridge/src/SpatialDetectionConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,19 +59,11 @@ void SpatialDetectionConverter::toRosMsg(std::shared_ptr<dai::SpatialImgDetectio
float yCenter = yMin + ySize / 2;
opDetectionMsg.detections[i].results.resize(1);

#if defined(IS_GALACTIC) || defined(IS_HUMBLE)
opDetectionMsg.detections[i].results[0].class_id = std::to_string(inNetData->detections[i].label);
#elif IS_ROS2
opDetectionMsg.detections[i].results[0].id = std::to_string(inNetData->detections[i].label);
opDetectionMsg.detections[i].results[0].score = inNetData->detections[i].confidence;
#endif
#ifdef IS_HUMBLE
opDetectionMsg.detections[i].bbox.center.position.x = xCenter;

opDetectionMsg.detections[i].bbox.center.position.x = xCenter;
opDetectionMsg.detections[i].bbox.center.position.y = yCenter;
#else
opDetectionMsg.detections[i].bbox.center.x = xCenter;
opDetectionMsg.detections[i].bbox.center.y = yCenter;
#endif
opDetectionMsg.detections[i].bbox.size_x = xSize;
opDetectionMsg.detections[i].bbox.size_y = ySize;

Expand Down Expand Up @@ -148,4 +140,4 @@ void SpatialDetectionConverter::toRosVisionMsg(std::shared_ptr<dai::SpatialImgDe
}

} // namespace ros
} // namespace dai
} // namespace dai

0 comments on commit 090a291

Please sign in to comment.