Skip to content

Commit

Permalink
Remove cras::expected
Browse files Browse the repository at this point in the history
  • Loading branch information
john-maidbot committed Aug 12, 2023
1 parent d82b3ba commit 543830f
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class DracoPublisher
static void registerNormalField(const std::string & field);

private:
cras::expected<std::unique_ptr<draco::PointCloud>, std::string> convertPC2toDraco(
tl::expected<std::unique_ptr<draco::PointCloud>, std::string> convertPC2toDraco(
const sensor_msgs::msg::PointCloud2 & PC2, const std::string & topic, bool deduplicate,
bool expert_encoding) const;

Expand Down
16 changes: 8 additions & 8 deletions 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 <point_cloud_transport/expected.hpp>
#include <tl/expected.hpp>

#include <draco_point_cloud_transport/cloud.hpp>
#include <draco_point_cloud_transport/draco_publisher.hpp>
Expand Down Expand Up @@ -317,7 +317,7 @@ void DracoPublisher::declareParameters(const std::string & base_topic)
setParamCallback(param_change_callback);
}

cras::expected<std::unique_ptr<draco::PointCloud>, std::string> DracoPublisher::convertPC2toDraco(
tl::expected<std::unique_ptr<draco::PointCloud>, std::string> DracoPublisher::convertPC2toDraco(
const sensor_msgs::msg::PointCloud2 & PC2, const std::string & topic, bool deduplicate,
bool expert_encoding) const
{
Expand Down Expand Up @@ -411,7 +411,7 @@ cras::expected<std::unique_ptr<draco::PointCloud>, std::string> DracoPublisher::
case sensor_msgs::msg::PointField::FLOAT64: attribute_data_type = draco::DT_FLOAT64;
rgba_tweak_64bit = true;
break;
default: return cras::make_unexpected("Invalid data type in PointCloud2 to Draco conversion");
default: return tl::make_unexpected("Invalid data type in PointCloud2 to Draco conversion");
}
// attribute data type switch end

Expand Down Expand Up @@ -439,7 +439,7 @@ cras::expected<std::unique_ptr<draco::PointCloud>, std::string> DracoPublisher::
std::unique_ptr<draco::PointCloud> pc = builder.Finalize(deduplicate);

if (pc == nullptr) {
return cras::make_unexpected(
return tl::make_unexpected(
"Conversion from sensor_msgs::msg::PointCloud2 to Draco::PointCloud failed");
}

Expand All @@ -454,7 +454,7 @@ cras::expected<std::unique_ptr<draco::PointCloud>, std::string> DracoPublisher::
pc->AddMetadata(std::move(metadata));

if ((pc->num_points() != number_of_points) && !deduplicate) {
return cras::make_unexpected(
return tl::make_unexpected(
"Number of points in Draco::PointCloud differs from sensor_msgs::msg::PointCloud2!");
}

Expand Down Expand Up @@ -489,7 +489,7 @@ DracoPublisher::TypedEncodeResult DracoPublisher::encodeTyped(
rawDense, base_topic_, config_.deduplicate,
config_.expert_attribute_types);
if (!res) {
return cras::make_unexpected(res.error());
return tl::make_unexpected(res.error());
}

const auto & pc = res.value();
Expand Down Expand Up @@ -551,7 +551,7 @@ DracoPublisher::TypedEncodeResult DracoPublisher::encodeTyped(

if (status.code() != 0) {
// TODO(anyone): Fix with proper format
return cras::make_unexpected(
return tl::make_unexpected(
"Draco encoder returned code " + std::to_string(
status.code()) + ": " + status.error_msg() + ".");
}
Expand Down Expand Up @@ -594,7 +594,7 @@ DracoPublisher::TypedEncodeResult DracoPublisher::encodeTyped(
draco::Status status = encoder.EncodePointCloudToBuffer(*pc, &encode_buffer);

if (!status.ok()) {
return cras::make_unexpected(
return tl::make_unexpected(
"Draco encoder returned code " + std::to_string(
status.code()) + ": " + status.error_msg() + ".");
}
Expand Down
12 changes: 6 additions & 6 deletions 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 <point_cloud_transport/expected.hpp>
#include <tl/expected.hpp>

#include <draco_point_cloud_transport/draco_subscriber.hpp>

Expand Down Expand Up @@ -84,7 +84,7 @@ void DracoSubscriber::declareParameters()
}

//! Method for converting into sensor_msgs::msg::PointCloud2
cras::expected<bool, std::string> convertDracoToPC2(
tl::expected<bool, std::string> convertDracoToPC2(
const draco::PointCloud & pc,
const point_cloud_interfaces::msg::CompressedPointCloud2 & compressed_PC2,
sensor_msgs::msg::PointCloud2 & PC2)
Expand All @@ -104,7 +104,7 @@ cras::expected<bool, std::string> convertDracoToPC2(

// check if attribute is valid
if (!attribute->IsValid()) {
return cras::make_unexpected(
return tl::make_unexpected(
std::string(
"In point_cloud_transport::DracoToPC2, attribute of Draco pointcloud is not valid!"));
}
Expand Down Expand Up @@ -144,7 +144,7 @@ DracoSubscriber::DecodeResult DracoSubscriber::decodeTyped(

// empty buffer
if (compressed_data_size == 0) {
return cras::make_unexpected("Received compressed Draco message with zero length.");
return tl::make_unexpected("Received compressed Draco message with zero length.");
}

draco::DecoderBuffer decode_buffer;
Expand Down Expand Up @@ -177,7 +177,7 @@ DracoSubscriber::DecodeResult DracoSubscriber::decodeTyped(
// decode buffer into draco point cloud
const auto res = decoder.DecodePointCloudFromBuffer(&decode_buffer);
if (!res.ok()) {
return cras::make_unexpected(
return tl::make_unexpected(
"Draco decoder returned code " + std::to_string(
res.status().code()) + ": " + res.status().error_msg() + ".");
}
Expand All @@ -187,7 +187,7 @@ DracoSubscriber::DecodeResult DracoSubscriber::decodeTyped(
auto message = std::make_shared<sensor_msgs::msg::PointCloud2>();
const auto convertRes = convertDracoToPC2(*decoded_pc, compressed, *message);
if (!convertRes) {
return cras::make_unexpected(convertRes.error());
return tl::make_unexpected(convertRes.error());
}

return message;
Expand Down

0 comments on commit 543830f

Please sign in to comment.