Skip to content

Commit

Permalink
Added feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Feb 15, 2024
1 parent f0424d5 commit 1df003f
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -263,8 +263,7 @@ class PointCloudTransport : public PointCloudTransportLoader
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, rmw_qos_profile_t custom_qos,
void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &) const, T * obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr,
bool /*allow_concurrent_callbacks*/ = false)
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, custom_qos, std::bind(
Expand All @@ -276,8 +275,7 @@ class PointCloudTransport : public PointCloudTransportLoader
point_cloud_transport::Subscriber subscribe(
const std::string & base_topic, uint32_t queue_size,
void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &) const, T * obj,
const point_cloud_transport::TransportHints * transport_hints = nullptr,
bool /*allow_concurrent_callbacks*/ = false)
const point_cloud_transport::TransportHints * transport_hints = nullptr)
{
return subscribe(
base_topic, queue_size, std::bind(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class PublisherPlugin
/// or an error message.
///
POINT_CLOUD_TRANSPORT_PUBLIC
virtual EncodeResult encode(const sensor_msgs::msg::PointCloud2 & raw) const;
virtual EncodeResult encode(const sensor_msgs::msg::PointCloud2 & raw) const = 0;

//! Publish a point cloud using the transport associated with this PublisherPlugin.
virtual void publish(const sensor_msgs::msg::PointCloud2 & message) const = 0;
Expand Down
8 changes: 0 additions & 8 deletions point_cloud_transport/src/publisher_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,6 @@
namespace point_cloud_transport
{

PublisherPlugin::EncodeResult PublisherPlugin::encode(const sensor_msgs::msg::PointCloud2 & /*raw*/)
const
{
// TODO(ahcorde): Review this, infinite recursion
// return this->encode(raw);
return std::nullopt;
}

void PublisherPlugin::advertise(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
Expand Down

0 comments on commit 1df003f

Please sign in to comment.