Skip to content

Commit

Permalink
Use tl_expected from rcpputils (#42)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Feb 16, 2024
1 parent 3d5816b commit e058ff4
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 2 deletions.
2 changes: 2 additions & 0 deletions draco_point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ find_package(pluginlib REQUIRED)
find_package(point_cloud_interfaces REQUIRED)
find_package(point_cloud_transport REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcpputils REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)

Expand All @@ -19,6 +20,7 @@ set(dependencies
point_cloud_interfaces
point_cloud_transport
rclcpp
rcpputils
sensor_msgs
std_msgs
)
Expand Down
1 change: 1 addition & 0 deletions draco_point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>point_cloud_interfaces</depend>
<depend>point_cloud_transport</depend>
<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>

Expand Down
2 changes: 1 addition & 1 deletion draco_point_cloud_transport/src/draco_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <vector>

#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>
#include <tl_expected/expected.hpp>
#include <rcpputils/tl_expected/expected.hpp>

#include <draco_point_cloud_transport/cloud.hpp>
#include <draco_point_cloud_transport/draco_publisher.hpp>
Expand Down
2 changes: 1 addition & 1 deletion draco_point_cloud_transport/src/draco_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>
#include <tl_expected/expected.hpp>
#include <rcpputils/tl_expected/expected.hpp>

#include <draco_point_cloud_transport/draco_subscriber.hpp>

Expand Down

0 comments on commit e058ff4

Please sign in to comment.