Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added point_cloud_transport_py #26

Merged
merged 2 commits into from
Sep 6, 2023

Conversation

ahcorde
Copy link
Collaborator

@ahcorde ahcorde commented Aug 28, 2023

Sorry for the big refactoring

The idea is to split the current package in two.

  • point_cloud_transport (cpp API)
  • point_cloud_transport_py (other package like moveit2 or rosbag2 has a specific package for the python bindings)

Examples included in this PR ros-perception/point_cloud_transport_tutorial#5

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
@ahcorde ahcorde self-assigned this Aug 28, 2023
@ahcorde ahcorde changed the title Added point_cloud_transport_pu Added point_cloud_transport_py Sep 5, 2023
Copy link
Collaborator

@john-maidbot john-maidbot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A few non-blocking comments but otherwise looks good to me!
Very nice reorganization 👍

@@ -151,12 +151,24 @@ class PointCloudTransport : public PointCloudTransportLoader
return ret;
}

//! Advertise a PointCloud2 topic, simple version.
POINT_CLOUD_TRANSPORT_PUBLIC
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this necessary, considering the existing definition of advertise on line 167 below?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah is this to make the python binding easier?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes, it's to simplify things

self.transport_publishers[transport].publish(compressed_buffer)
else:
self.get_logger().error('Error encoding message!')
# for transport, transport_info in self.topics_to_publish.items():
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you need to uncomment this for loop, right?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

publisher.py and subscriber.py should be removed. This functionality is available from pybind11

&point_cloud_transport::Publisher::getNumSubscribers,
"Returns the number of subscribers this publisher is connected to.")
.def("shutdown", &point_cloud_transport::Publisher::shutdown,
"Unsubscribe the callback associated with this Publisher.")
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you reword this please?

.def("advertise",
pybind11::overload_cast<const std::string &, uint32_t>(
&point_cloud_transport::PointCloudTransport::advertise));
// TODO(ahcorde)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just noting that i am ok with merging without addressing this TODO. But could you please make an issue pointing to the TODO so we dont forget about it?

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
@ahcorde ahcorde merged commit 737f082 into rolling Sep 6, 2023
3 checks passed
@ahcorde ahcorde deleted the ahcorde/rolling/point_cloud_transport_py branch September 6, 2023 11:14
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants