Skip to content

Commit

Permalink
feat(traffic_light_fine_detector)!: tier4_debug_msgs changed to autow…
Browse files Browse the repository at this point in the history
…are_internal_debug_msgs in traffic_light_fine_detector (#9900)

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 authored Jan 23, 2025
1 parent fa4f023 commit 231f027
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions perception/autoware_traffic_light_fine_detector/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@ ROIs detected from YOLOX will be selected by a combination of `expect/rois`. At

### Output

| Name | Type | Description |
| --------------------- | -------------------------------------------------- | ---------------------------- |
| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois |
| `~/debug/exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | The time taken for inference |
| Name | Type | Description |
| --------------------- | --------------------------------------------------- | ---------------------------- |
| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois |
| `~/debug/exe_time_ms` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The time taken for inference |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_tensorrt_yolox</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>message_filters</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_perception_msgs</depend>

<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,8 +101,8 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt

std::lock_guard<std::mutex> lock(connect_mutex_);
output_roi_pub_ = this->create_publisher<TrafficLightRoiArray>("~/output/rois", 1);
exe_time_pub_ =
this->create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/debug/exe_time_ms", 1);
exe_time_pub_ = this->create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"~/debug/exe_time_ms", 1);
if (is_approximate_sync_) {
approximate_sync_.reset(
new ApproximateSync(ApproximateSyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_));
Expand Down Expand Up @@ -208,7 +208,7 @@ void TrafficLightFineDetectorNode::callback(
const auto exe_end_time = high_resolution_clock::now();
const double exe_time =
std::chrono::duration_cast<milliseconds>(exe_end_time - exe_start_time).count();
tier4_debug_msgs::msg::Float32Stamped exe_time_msg;
autoware_internal_debug_msgs::msg::Float32Stamped exe_time_msg;
exe_time_msg.data = exe_time;
exe_time_msg.stamp = this->now();
exe_time_pub_->publish(exe_time_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@
#include <opencv2/highgui/highgui.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_stamped.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>
#include <tier4_perception_msgs/msg/traffic_light_roi_array.hpp>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
Expand Down Expand Up @@ -148,7 +148,7 @@ class TrafficLightFineDetectorNode : public rclcpp::Node
message_filters::Subscriber<TrafficLightRoiArray> expect_roi_sub_;
std::mutex connect_mutex_;
rclcpp::Publisher<TrafficLightRoiArray>::SharedPtr output_roi_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr exe_time_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr exe_time_pub_;
rclcpp::TimerBase::SharedPtr timer_;

typedef message_filters::sync_policies::ExactTime<
Expand Down

0 comments on commit 231f027

Please sign in to comment.