Skip to content

Commit

Permalink
use vision_msgs and not geometry_msgs
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed May 15, 2023
1 parent a93b325 commit 124e4ba
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 4 deletions.
2 changes: 1 addition & 1 deletion zbar_ros/src/barcode_reader_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
point_it != symbol_it->point_end();
++point_it)
{
geometry_msgs::msg::Point point;
vision_msgs::msg::Point2D point;
point.x = (*point_it).x;
point.y = (*point_it).y;
RCLCPP_DEBUG(get_logger(), " Point: %f, %f", point.x, point.y);
Expand Down
4 changes: 2 additions & 2 deletions zbar_ros_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,12 @@ endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(vision_msgs REQUIRED)

# generate interfaces
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Symbol.msg"
DEPENDENCIES geometry_msgs
DEPENDENCIES vision_msgs
)

ament_export_dependencies(rosidl_default_runtime)
Expand Down
2 changes: 1 addition & 1 deletion zbar_ros_interfaces/msg/Symbol.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
string data
geometry_msgs/Point[] points
vision_msgs/Point2D[] points
2 changes: 2 additions & 0 deletions zbar_ros_interfaces/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>vision_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

Expand Down

0 comments on commit 124e4ba

Please sign in to comment.