Skip to content

Commit

Permalink
feat(autoware_image_diagnostics): tier4_debug_msgs changed to autowar…
Browse files Browse the repository at this point in the history
…e_internal_debug_msgs in autoware_image_diagnostics (#9918)

feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_image_diagnostics

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 authored Jan 15, 2025
1 parent acaa40c commit b65e042
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 15 deletions.
14 changes: 7 additions & 7 deletions sensing/autoware_image_diagnostics/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@ After all image's blocks state are evaluated, the whole image status is summariz

### Output

| Name | Type | Description |
| ----------------------------------- | --------------------------------------- | ------------------------------------- |
| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image |
| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image |
| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization |
| `image_diag/image_state_diag` | `tier4_debug_msgs::msg::Int32Stamped` | image diagnostics status value |
| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics |
| Name | Type | Description |
| ----------------------------------- | ------------------------------------------------- | ------------------------------------- |
| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image |
| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image |
| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization |
| `image_diag/image_state_diag` | `autoware_internal_debug_msgs::msg::Int32Stamped` | image diagnostics status value |
| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics |

## Parameters

Expand Down
2 changes: 1 addition & 1 deletion sensing/autoware_image_diagnostics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>cv_bridge</depend>
<depend>diagnostic_updater</depend>
<depend>image_transport</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ ImageDiagNode::ImageDiagNode(const rclcpp::NodeOptions & node_options)
dft_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/dft_image");
gray_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/gray_image");

image_state_pub_ = create_publisher<tier4_debug_msgs::msg::Int32Stamped>(
image_state_pub_ = create_publisher<autoware_internal_debug_msgs::msg::Int32Stamped>(
"image_diag/image_state_diag", rclcpp::SensorDataQoS());

updater_.setHardwareID("Image_Diagnostics");
Expand Down Expand Up @@ -225,7 +225,7 @@ void ImageDiagNode::ImageChecker(const sensor_msgs::msg::Image::ConstSharedPtr i
} else {
params_.diagnostic_status = 0;
}
tier4_debug_msgs::msg::Int32Stamped image_state_out;
autoware_internal_debug_msgs::msg::Int32Stamped image_state_out;
image_state_out.data = params_.diagnostic_status;
image_state_pub_->publish(image_state_out);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
#include <opencv2/imgproc/imgproc.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/float32_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/int32_stamped.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp>
Expand Down Expand Up @@ -95,8 +95,9 @@ class ImageDiagNode : public rclcpp::Node
image_transport::Publisher block_diag_image_pub_;
image_transport::Publisher dft_image_pub_;
image_transport::Publisher gray_image_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr average_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Int32Stamped>::SharedPtr image_state_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr
average_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Int32Stamped>::SharedPtr image_state_pub_;
};

} // namespace autoware::image_diagnostics
Expand Down

0 comments on commit b65e042

Please sign in to comment.