Skip to content

Commit

Permalink
Fix conflicts
Browse files Browse the repository at this point in the history
  • Loading branch information
john-maidbot committed Sep 10, 2023
2 parents c16b0d9 + 411e2be commit a655576
Show file tree
Hide file tree
Showing 19 changed files with 520 additions and 23 deletions.
8 changes: 6 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@ This metapackage contains the most common plugins for pointcloud compression usi

Currently provided are:

- [draco_point_cloud_transport](https://github.com/ctu-vras/point_cloud_transport_plugins/tree/master/draco_point_cloud_transport) - A library using Google Draco to compress the pointclouds.
- [draco_point_cloud_transport](https://github.com/ros-perception/point_cloud_transport_plugins/tree/rolling/draco_point_cloud_transport) - A library using Google Draco to compress the pointclouds.

More transports can be added. Pull requests are welcome!
- [zlib_point_cloud_transport](https://github.com/ros-perception/point_cloud_transport_plugins/tree/rolling/zlib_point_cloud_transport) - A libraory using zlib to compress the pointclouds.

- [zstd_point_cloud_transport](https://github.com/ros-perception/point_cloud_transport_plugins/tree/master/zstd_point_cloud_transport) - A library using ZSTD to compress the pointclouds.

More transports can be added. Pull requests are welcome!
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
2 changes: 1 addition & 1 deletion draco_point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>draco_point_cloud_transport</name>
<version>1.0.5</version>
<version>0.0.0</version>
<description>
draco_point_cloud_transport provides a plugin to point_cloud_transport for sending point clouds
encoded with KD tree compression.
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
2 changes: 1 addition & 1 deletion point_cloud_interfaces/msg/CompressedPointCloud2.msg
Original file line number Diff line number Diff line change
Expand Up @@ -18,5 +18,5 @@ uint8[] compressed_data

bool is_dense

# type of encoding used (e.g. draco, zlib, etc...)
# compression format used (e.g. draco, zlib, etc.)
string format
2 changes: 1 addition & 1 deletion point_cloud_interfaces/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>point_cloud_interfaces</name>
<version>1.0.5</version>
<version>0.0.0</version>
<description>
msg definitions for use with point_cloud_transport plugins.
</description>
Expand Down
2 changes: 1 addition & 1 deletion point_cloud_transport.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,4 @@ repositories:
point_cloud_transport:
type: git
url: https://github.com/john-maidbot/point_cloud_transport
version: ros2
version: rolling
3 changes: 2 additions & 1 deletion point_cloud_transport_plugins/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>point_cloud_transport_plugins</name>
<version>1.0.5</version>
<version>0.0.0</version>
<description>Metapackage with common point_cloud_transport plugins</description>
<author>Jakub Paplham</author>
<maintainer email="[email protected]">Martin Pecka</maintainer>
Expand All @@ -15,6 +15,7 @@
<exec_depend>draco_point_cloud_transport</exec_depend>
<exec_depend>point_cloud_interfaces</exec_depend>
<exec_depend>zlib_point_cloud_transport</exec_depend>
<exec_depend>zstd_point_cloud_transport</exec_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
2 changes: 1 addition & 1 deletion zlib_point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>zlib_point_cloud_transport</name>
<version>1.0.5</version>
<version>0.0.0</version>
<description>
zlib_point_cloud_transport provides a plugin to point_cloud_transport for sending point clouds
encoded with zlib
Expand Down
1 change: 1 addition & 0 deletions zlib_point_cloud_transport/src/zlib_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ ZlibPublisher::TypedEncodeResult ZlibPublisher::encodeTyped(
compressed.is_dense = raw.is_dense;
compressed.header = raw.header;
compressed.fields = raw.fields;
compressed.format = getTransportName();

compressed.format = getTransportName();

Expand Down
54 changes: 54 additions & 0 deletions zstd_point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
cmake_minimum_required(VERSION 3.10.2)

set(CMAKE_CXX_STANDARD 17)

project(zstd_point_cloud_transport)

find_package(ament_cmake REQUIRED)
find_package(pluginlib REQUIRED)
find_package(point_cloud_interfaces REQUIRED)
find_package(point_cloud_transport REQUIRED)
find_package(rclcpp REQUIRED)

set(dependencies
pluginlib
point_cloud_interfaces
point_cloud_transport
rclcpp
)

include_directories(include)

add_library(${PROJECT_NAME}
SHARED
src/zstd_publisher.cpp
src/zstd_subscriber.cpp
src/manifest.cpp
)

target_link_libraries(${PROJECT_NAME} zstd)

ament_target_dependencies(${PROJECT_NAME} ${dependencies})

install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

install(
DIRECTORY include/${PROJECT_NAME}/
DESTINATION include/${PROJECT_NAME}
)

pluginlib_export_plugin_description_file(point_cloud_transport zstd_plugins.xml)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_export_dependencies(${dependencies})
ament_package()
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_PUBLISHER_HPP_
#define ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_PUBLISHER_HPP_

#include <memory>
#include <string>

#include <sensor_msgs/msg/point_cloud2.hpp>

#include <point_cloud_transport/point_cloud_transport.hpp>

#include <point_cloud_transport/simple_publisher_plugin.hpp>
#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>


namespace zstd_point_cloud_transport
{

class ZstdPublisher
: public point_cloud_transport::SimplePublisherPlugin<
point_cloud_interfaces::msg::CompressedPointCloud2>
{
public:
std::string getTransportName() const override;

void declareParameters(const std::string & base_topic) override;

std::string getDataType() const override;

TypedEncodeResult encodeTyped(const sensor_msgs::msg::PointCloud2 & raw) const override;

private:
int encode_level_{7};
};
} // namespace zstd_point_cloud_transport

#endif // ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_PUBLISHER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_SUBSCRIBER_HPP_
#define ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_SUBSCRIBER_HPP_

#include <string>

#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>

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

namespace zstd_point_cloud_transport
{

class ZstdSubscriber
: public point_cloud_transport::SimpleSubscriberPlugin<
point_cloud_interfaces::msg::CompressedPointCloud2>
{
public:
std::string getTransportName() const override;

void declareParameters() override;

std::string getDataType() const override;

DecodeResult decodeTyped(const point_cloud_interfaces::msg::CompressedPointCloud2 & compressed)
const override;
};
} // namespace zstd_point_cloud_transport

#endif // ZSTD_POINT_CLOUD_TRANSPORT__ZSTD_SUBSCRIBER_HPP_
Loading

0 comments on commit a655576

Please sign in to comment.