Skip to content

Commit

Permalink
Fixed SubscriberFilter linking issue on windows
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 Mar 8, 2024
1 parent 47376a7 commit dec046e
Show file tree
Hide file tree
Showing 4 changed files with 115 additions and 56 deletions.
1 change: 1 addition & 0 deletions point_cloud_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ add_library(${PROJECT_NAME}
src/publisher_plugin.cpp
src/raw_subscriber.cpp
src/single_subscriber_publisher.cpp
src/subscriber_filter.cpp
src/subscriber.cpp
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,23 +73,14 @@ class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::
POINT_CLOUD_TRANSPORT_PUBLIC
SubscriberFilter(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
const std::string & transport)
{
subscribe(node, base_topic, transport);
}
const std::string & transport);

//! Empty constructor, use subscribe() to subscribe to a topic
POINT_CLOUD_TRANSPORT_PUBLIC
SubscriberFilter()
{
}
SubscriberFilter();

POINT_CLOUD_TRANSPORT_PUBLIC
~SubscriberFilter()
{
unsubscribe();
}

~SubscriberFilter();
///
/// \brief Subscribe to a topic. If this Subscriber is already subscribed to a topic,
/// this function will first unsubscribe.
Expand All @@ -105,48 +96,26 @@ class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::
const std::string & base_topic,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())
{
unsubscribe();
sub_ = point_cloud_transport::create_subscription(
node, base_topic,
std::bind(&SubscriberFilter::cb, this, std::placeholders::_1),
transport, custom_qos, options);
}
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

//! Force immediate unsubscription of this subscriber from its topic
POINT_CLOUD_TRANSPORT_PUBLIC
void unsubscribe()
{
sub_.shutdown();
}
void unsubscribe();

POINT_CLOUD_TRANSPORT_PUBLIC
std::string getTopic() const
{
return sub_.getTopic();
}
std::string getTopic() const;

//! Returns the number of publishers this subscriber is connected to.
POINT_CLOUD_TRANSPORT_PUBLIC
uint32_t getNumPublishers() const
{
return sub_.getNumPublishers();
}
uint32_t getNumPublishers() const;

//! Returns the name of the transport being used.
POINT_CLOUD_TRANSPORT_PUBLIC
std::string getTransport() const
{
return sub_.getTransport();
}
std::string getTransport() const;

//! Returns the internal point_cloud_transport::Subscriber object.
POINT_CLOUD_TRANSPORT_PUBLIC
const Subscriber & getSubscriber() const
{
return sub_;
}
const Subscriber & getSubscriber() const;

private:
void cb(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & m)
Expand Down
90 changes: 90 additions & 0 deletions point_cloud_transport/src/subscriber_filter.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// 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.

#include "point_cloud_transport/subscriber_filter.hpp"

#include <memory>
#include <string>

namespace point_cloud_transport
{
SubscriberFilter::SubscriberFilter(
std::shared_ptr<rclcpp::Node> node, const std::string & base_topic,
const std::string & transport)
{
subscribe(node, base_topic, transport);
}

SubscriberFilter::SubscriberFilter()
{
}

SubscriberFilter::~SubscriberFilter()
{
unsubscribe();
}

void SubscriberFilter::subscribe(
std::shared_ptr<rclcpp::Node> node,
const std::string & base_topic,
const std::string & transport,
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options)
{
unsubscribe();
sub_ = point_cloud_transport::create_subscription(
node, base_topic,
std::bind(&SubscriberFilter::cb, this, std::placeholders::_1),
transport, custom_qos, options);
}

void SubscriberFilter::unsubscribe()
{
sub_.shutdown();
}

std::string SubscriberFilter::getTopic() const
{
return sub_.getTopic();
}

uint32_t SubscriberFilter::getNumPublishers() const
{
return sub_.getNumPublishers();
}

std::string SubscriberFilter::getTransport() const
{
return sub_.getTransport();
}

const Subscriber & SubscriberFilter::getSubscriber() const
{
return sub_;
}
} // namespace point_cloud_transport
31 changes: 15 additions & 16 deletions point_cloud_transport/test/test_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,25 +59,24 @@ void callback(
(void) msg2;
}

// TEST_F(TestSubscriber, create_and_release_filter)
// {
// typedef message_filters::sync_policies::ApproximateTime<
// sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2>
// ApproximateTimePolicy;
TEST_F(TestSubscriber, create_and_release_filter)
{
typedef message_filters::sync_policies::ApproximateTime<
sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2>
ApproximateTimePolicy;

// TODO(ahcorde): Review this test on Windows
// point_cloud_transport::SubscriberFilter pcl_sub1(node_, "pointcloud1", "raw");
// point_cloud_transport::SubscriberFilter pcl_sub2(node_, "pointcloud2", "raw");
point_cloud_transport::SubscriberFilter pcl_sub1(node_, "pointcloud1", "raw");
point_cloud_transport::SubscriberFilter pcl_sub2(node_, "pointcloud2", "raw");

// auto sync = std::make_shared<message_filters::Synchronizer<ApproximateTimePolicy>>(
// ApproximateTimePolicy(
// 10), pcl_sub1, pcl_sub2);
// sync->registerCallback(std::bind(callback, std::placeholders::_1, std::placeholders::_2));
auto sync = std::make_shared<message_filters::Synchronizer<ApproximateTimePolicy>>(
ApproximateTimePolicy(
10), pcl_sub1, pcl_sub2);
sync->registerCallback(std::bind(callback, std::placeholders::_1, std::placeholders::_2));

// pcl_sub1.unsubscribe();
// pcl_sub2.unsubscribe();
// sync.reset();
// }
pcl_sub1.unsubscribe();
pcl_sub2.unsubscribe();
sync.reset();
}

int main(int argc, char ** argv)
{
Expand Down

0 comments on commit dec046e

Please sign in to comment.