Skip to content

Commit

Permalink
Change tl_expected for rcpputils (#48) (#52)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Feb 14, 2024
1 parent 402d868 commit cda0c06
Show file tree
Hide file tree
Showing 5 changed files with 7 additions and 7 deletions.
6 changes: 3 additions & 3 deletions point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tl_expected REQUIRED)
find_package(rcpputils REQUIRED)

# Build libpoint_cloud_transport
add_library(${PROJECT_NAME}
Expand All @@ -41,7 +41,7 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
message_filters::message_filters
rclcpp::rclcpp
${sensor_msgs_TARGETS}
tl_expected::tl_expected)
rcpputils::rcpputils)
target_link_libraries(${PROJECT_NAME} PRIVATE
pluginlib::pluginlib)

Expand Down Expand Up @@ -117,7 +117,7 @@ ament_export_include_directories("include/${PROJECT_NAME}")

ament_export_targets(export_${PROJECT_NAME})

ament_export_dependencies(message_filters rclcpp sensor_msgs pluginlib tl_expected)
ament_export_dependencies(message_filters rclcpp sensor_msgs pluginlib rcpputils)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#include "rclcpp/node.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tl_expected/expected.hpp>
#include <rcpputils/tl_expected/expected.hpp>

#include <point_cloud_transport/single_subscriber_publisher.hpp>
#include "point_cloud_transport/visibility_control.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <rclcpp/rclcpp.hpp>
#include "rclcpp/serialization.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tl_expected/expected.hpp>
#include <rcpputils/tl_expected/expected.hpp>

#include <point_cloud_transport/point_cloud_common.hpp>
#include <point_cloud_transport/publisher_plugin.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tl_expected/expected.hpp>
#include <rcpputils/tl_expected/expected.hpp>

#include <point_cloud_transport/transport_hints.hpp>

Expand Down
2 changes: 1 addition & 1 deletion point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
<depend>pluginlib</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>sensor_msgs</depend>
<depend>tl_expected</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down

0 comments on commit cda0c06

Please sign in to comment.