Skip to content

Commit

Permalink
Remove cras expected.hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
john-maidbot committed Aug 12, 2023
1 parent 3146883 commit 581fade
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 83 deletions.
73 changes: 0 additions & 73 deletions include/point_cloud_transport/expected.hpp

This file was deleted.

4 changes: 2 additions & 2 deletions include/point_cloud_transport/publisher_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@

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

#include <point_cloud_transport/expected.hpp>
#include <point_cloud_transport/single_subscriber_publisher.hpp>
#include "point_cloud_transport/visibility_control.hpp"

Expand All @@ -52,7 +52,7 @@ class POINT_CLOUD_TRANSPORT_PUBLIC PublisherPlugin
public:
/// \brief Result of cloud encoding. Either an holding the compressed cloud,
/// empty value or error message.
typedef cras::expected<std::optional<const std::shared_ptr<rclcpp::SerializedMessage>>,
typedef tl::expected<std::optional<const std::shared_ptr<rclcpp::SerializedMessage>>,
std::string> EncodeResult;

PublisherPlugin() = default;
Expand Down
8 changes: 4 additions & 4 deletions include/point_cloud_transport/simple_publisher_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
#include <rclcpp/rclcpp.hpp>
#include "rclcpp/serialization.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tl/expected.hpp>

#include <point_cloud_transport/expected.hpp>
#include <point_cloud_transport/point_cloud_common.hpp>
#include <point_cloud_transport/publisher_plugin.hpp>
#include <point_cloud_transport/single_subscriber_publisher.hpp>
Expand Down Expand Up @@ -75,7 +75,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
public:
/// \brief Result of cloud encoding. Either the compressed cloud message,
/// empty value, or error message.
typedef cras::expected<std::optional<M>, std::string> TypedEncodeResult;
typedef tl::expected<std::optional<M>, std::string> TypedEncodeResult;

~SimplePublisherPlugin()
{
Expand Down Expand Up @@ -114,7 +114,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
}

void setParamCallback(
rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
param_change_callback)
{
if (simple_impl_) {
Expand Down Expand Up @@ -171,7 +171,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin
// encode the message using the expected transport method
auto res = this->encodeTyped(raw);
if (!res) {
return cras::make_unexpected(res.error());
return tl::make_unexpected(res.error());
}
if (!res.value()) {
return std::nullopt;
Expand Down
4 changes: 2 additions & 2 deletions include/point_cloud_transport/simple_subscriber_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
}

void setParamCallback(
rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
param_change_callback)
{
if (impl_) {
Expand Down Expand Up @@ -134,7 +134,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin
auto serializer = rclcpp::Serialization<M>();
serializer.deserialize_message(compressed.get(), msg.get());
} catch (const std::exception & e) {
return cras::make_unexpected(
return tl::make_unexpected(
"Error deserializing message for transport decoder: " + std::string(
e.what()) + ".");
}
Expand Down
4 changes: 2 additions & 2 deletions include/point_cloud_transport/subscriber_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tl/expected.hpp>

#include <point_cloud_transport/expected.hpp>
#include <point_cloud_transport/transport_hints.hpp>

#include "point_cloud_transport/visibility_control.hpp"
Expand All @@ -57,7 +57,7 @@ class POINT_CLOUD_TRANSPORT_PUBLIC SubscriberPlugin
public:
/// \brief Result of cloud decoding. Either a `sensor_msgs::msg::PointCloud2`
/// holding the raw message, empty value or error message.
typedef cras::expected<std::optional<sensor_msgs::msg::PointCloud2::ConstSharedPtr>,
typedef tl::expected<std::optional<sensor_msgs::msg::PointCloud2::ConstSharedPtr>,
std::string> DecodeResult;

SubscriberPlugin() = default;
Expand Down

0 comments on commit 581fade

Please sign in to comment.