Skip to content

Commit

Permalink
Added point_cloud_transport_py (#26)
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 Sep 6, 2023
1 parent cae7437 commit 737f082
Show file tree
Hide file tree
Showing 59 changed files with 347 additions and 263 deletions.
File renamed without changes.
33 changes: 0 additions & 33 deletions CMakeLists.txt → point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,11 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake_ros REQUIRED)
find_package(ament_cmake_python REQUIRED)

find_package(message_filters REQUIRED)
find_package(pluginlib REQUIRED)
find_package(pybind11 REQUIRED)
find_package(pybind11_vendor REQUIRED)
find_package(python_cmake_module REQUIRED)
find_package(Python3 REQUIRED COMPONENTS Interpreter Development)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclpy REQUIRED)
find_package(sensor_msgs REQUIRED)

include_directories(
Expand Down Expand Up @@ -105,33 +99,6 @@ target_link_libraries(list_transports
${PROJECT_NAME}
pluginlib::pluginlib)


# Install Python modules
ament_python_install_package(${PROJECT_NAME})

# Python bindings
pybind11_add_module(_codec SHARED
src/pybind_codec.cpp
)
target_link_libraries(_codec PRIVATE
${PROJECT_NAME}
pluginlib::pluginlib
)

# Install cython modules as sub-modules of the project
install(
TARGETS
_codec
DESTINATION "${PYTHON_INSTALL_DIR}/${PROJECT_NAME}"
)

# Install Python executables
install(PROGRAMS
point_cloud_transport/publisher.py
point_cloud_transport/subscriber.py
DESTINATION lib/${PROJECT_NAME}
)

# Install plugin descriptions
pluginlib_export_plugin_description_file(${PROJECT_NAME} default_plugins.xml)

Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
Empty file removed point_cloud_transport/__init__.py
Empty file.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -151,12 +151,24 @@ class PointCloudTransport : public PointCloudTransportLoader
return ret;
}

//! Advertise a PointCloud2 topic, simple version.
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher advertise(
const std::string & base_topic,
uint32_t queue_size)
{
rclcpp::PublisherOptions options = rclcpp::PublisherOptions();
rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
custom_qos.depth = queue_size;
return Publisher(node_, base_topic, pub_loader_, custom_qos, options);
}

//! Advertise a PointCloud2 topic, simple version.
POINT_CLOUD_TRANSPORT_PUBLIC
Publisher advertise(
const std::string & base_topic,
uint32_t queue_size,
const rclcpp::PublisherOptions & options = rclcpp::PublisherOptions())
const rclcpp::PublisherOptions & options)
{
rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
custom_qos.depth = queue_size;
Expand All @@ -172,6 +184,19 @@ class PointCloudTransport : public PointCloudTransportLoader
return Publisher(node_, base_topic, pub_loader_, custom_qos, options);
}

// //! Subscribe to a point cloud topic, version for arbitrary std::function object.
// POINT_CLOUD_TRANSPORT_PUBLIC
// point_cloud_transport::Subscriber subscribe(
// const std::string & base_topic,
// uint32_t queue_size,
// const std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> & callback)
// {
// rmw_qos_profile_t custom_qos = rmw_qos_profile_sensor_data;
// custom_qos.depth = queue_size;
// return subscribe(
// base_topic, custom_qos, callback, {}, nullptr);
// }

//! Advertise an PointCloud2 topic with subscriber status callbacks.
// TODO(ros2) Implement when SubscriberStatusCallback is available
// point_cloud_transport::Publisher advertise(const std::string& base_topic, uint32_t queue_size,
Expand Down
File renamed without changes.
File renamed without changes.
9 changes: 2 additions & 7 deletions package.xml → point_cloud_transport/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,16 @@

<license>BSD</license>

<url type="repository">https://github.com/ctu-vras/point_cloud_transport</url>
<url type="bugtracker">https://github.com/ctu-vras/point_cloud_transport/issues</url>
<url type="repository">https://github.com/ros-perception/point_cloud_transport</url>
<url type="bugtracker">https://github.com/ros-perception/point_cloud_transport/issues</url>

<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>ament_cmake_python</buildtool_depend>

<depend>message_filters</depend>
<depend>pybind11</depend>
<depend>pybind11_vendor</depend>
<depend>pluginlib</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>sensor_msgs</depend>
<depend>git</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_copyright</test_depend>
Expand Down
116 changes: 0 additions & 116 deletions point_cloud_transport/publisher.py

This file was deleted.

File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
105 changes: 0 additions & 105 deletions point_cloud_transport/subscriber.py

This file was deleted.

File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Loading

0 comments on commit 737f082

Please sign in to comment.