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

Support lifecycle node #304

Open
wants to merge 16 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 33 additions & 1 deletion image_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ find_package(ament_cmake_ros REQUIRED)
find_package(message_filters REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(sensor_msgs REQUIRED)

Expand All @@ -37,6 +38,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC
target_link_libraries(${PROJECT_NAME} PUBLIC
message_filters::message_filters
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${sensor_msgs_TARGETS})
target_link_libraries(${PROJECT_NAME} PRIVATE
pluginlib::pluginlib)
Expand Down Expand Up @@ -107,7 +109,7 @@ install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})

ament_export_targets(export_${PROJECT_NAME})

ament_export_dependencies(message_filters rclcpp sensor_msgs pluginlib)
ament_export_dependencies(message_filters rclcpp rclcpp_lifecycle sensor_msgs pluginlib)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand All @@ -131,30 +133,60 @@ if(BUILD_TESTING)
target_link_libraries(${PROJECT_NAME}-publisher ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-publisher_lifecycle test/test_publisher_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-publisher_lifecycle)
target_link_libraries(${PROJECT_NAME}-publisher_lifecycle ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-subscriber test/test_subscriber.cpp)
if(TARGET ${PROJECT_NAME}-subscriber)
target_link_libraries(${PROJECT_NAME}-subscriber ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-subscriber_lifecycle test/test_subscriber_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-subscriber_lifecycle)
target_link_libraries(${PROJECT_NAME}-subscriber_lifecycle ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-message_passing test/test_message_passing.cpp)
if(TARGET ${PROJECT_NAME}-message_passing)
target_link_libraries(${PROJECT_NAME}-message_passing ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-message_passing_lifecycle test/test_message_passing_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-message_passing_lifecycle)
target_link_libraries(${PROJECT_NAME}-message_passing_lifecycle ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-remapping test/test_remapping.cpp)
if(TARGET ${PROJECT_NAME}-remapping)
target_link_libraries(${PROJECT_NAME}-remapping ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-remapping_lifecycle test/test_remapping_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-remapping_lifecycle)
target_link_libraries(${PROJECT_NAME}-remapping_lifecycle ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-qos_override test/test_qos_override.cpp)
if(TARGET ${PROJECT_NAME}-qos_override)
target_link_libraries(${PROJECT_NAME}-qos_override ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-qos_override_lifecycle test/test_qos_override_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-qos_override_lifecycle)
target_link_libraries(${PROJECT_NAME}-qos_override_lifecycle ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-single_subscriber_publisher test/test_single_subscriber_publisher.cpp)
if(TARGET ${PROJECT_NAME}-single_subscriber_publisher)
target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-single_subscriber_publisher_lifecycle test/test_single_subscriber_publisher_lifecycle.cpp)
if(TARGET ${PROJECT_NAME}-single_subscriber_publisher_lifecycle)
target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher_lifecycle ${PROJECT_NAME})
endif()
endif()

ament_package()
15 changes: 14 additions & 1 deletion image_transport/include/image_transport/camera_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@

#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

#include "sensor_msgs/msg/image.hpp"
#include "sensor_msgs/msg/camera_info.hpp"
Expand Down Expand Up @@ -69,7 +70,14 @@ class CameraPublisher

IMAGE_TRANSPORT_PUBLIC
CameraPublisher(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
CameraPublisher(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions = rclcpp::PublisherOptions());
Expand Down Expand Up @@ -142,6 +150,11 @@ class CameraPublisher
bool operator==(const CameraPublisher & rhs) const {return impl_ == rhs.impl_;}

private:
void initialise(
const std::string & base_topic,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options);

struct Impl;
std::shared_ptr<Impl> impl_;
};
Expand Down
17 changes: 16 additions & 1 deletion image_transport/include/image_transport/camera_subscriber.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <string>

#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

#include "sensor_msgs/msg/camera_info.hpp"
#include "sensor_msgs/msg/image.hpp"
Expand Down Expand Up @@ -71,7 +72,15 @@ class CameraSubscriber

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
rmw_qos_profile_t = rmw_qos_profile_default);

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
Expand Down Expand Up @@ -120,6 +129,12 @@ class CameraSubscriber
bool operator==(const CameraSubscriber & rhs) const {return impl_ == rhs.impl_;}

private:
void initialise(
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos);

struct Impl;
std::shared_ptr<Impl> impl_;
};
Expand Down
42 changes: 38 additions & 4 deletions image_transport/include/image_transport/image_transport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,14 @@ namespace image_transport
*/
IMAGE_TRANSPORT_PUBLIC
Publisher create_publisher(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
Publisher create_publisher(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());
Expand All @@ -61,7 +68,16 @@ Publisher create_publisher(
*/
IMAGE_TRANSPORT_PUBLIC
Subscriber create_subscription(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
const Subscriber::Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

IMAGE_TRANSPORT_PUBLIC
Subscriber create_subscription(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
const Subscriber::Callback & callback,
const std::string & transport,
Expand All @@ -73,7 +89,14 @@ Subscriber create_subscription(
*/
IMAGE_TRANSPORT_PUBLIC
CameraPublisher create_camera_publisher(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions pub_options = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
CameraPublisher create_camera_publisher(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions pub_options = rclcpp::PublisherOptions());
Expand All @@ -83,7 +106,15 @@ CameraPublisher create_camera_publisher(
*/
IMAGE_TRANSPORT_PUBLIC
CameraSubscriber create_camera_subscription(
rclcpp::Node * node,
rclcpp::Node::SharedPtr node,
const std::string & base_topic,
const CameraSubscriber::Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber create_camera_subscription(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const std::string & base_topic,
const CameraSubscriber::Callback & callback,
const std::string & transport,
Expand Down Expand Up @@ -112,6 +143,9 @@ class ImageTransport
IMAGE_TRANSPORT_PUBLIC
explicit ImageTransport(rclcpp::Node::SharedPtr node);

IMAGE_TRANSPORT_PUBLIC
explicit ImageTransport(rclcpp_lifecycle::LifecycleNode::SharedPtr node);

IMAGE_TRANSPORT_PUBLIC
~ImageTransport();

Expand Down
16 changes: 15 additions & 1 deletion image_transport/include/image_transport/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@

#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

#include "sensor_msgs/msg/image.hpp"

Expand Down Expand Up @@ -70,12 +71,19 @@ class Publisher

IMAGE_TRANSPORT_PUBLIC
Publisher(
rclcpp::Node * nh,
rclcpp::Node::SharedPtr nh,
const std::string & base_topic,
PubLoaderPtr loader,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
Publisher(
rclcpp_lifecycle::LifecycleNode::SharedPtr nh,
const std::string & base_topic,
PubLoaderPtr loader,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());
/*!
* \brief Returns the number of subscribers that are currently connected to
* this Publisher.
Expand Down Expand Up @@ -122,6 +130,12 @@ class Publisher
bool operator==(const Publisher & rhs) const {return impl_ == rhs.impl_;}

private:
void initialise(
const std::string & base_topic,
PubLoaderPtr loader,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options);

struct Impl;
std::shared_ptr<Impl> impl_;
};
Expand Down
60 changes: 57 additions & 3 deletions image_transport/include/image_transport/publisher_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,10 @@

#include <string>
#include <vector>
#include <memory>

#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "sensor_msgs/msg/image.hpp"

#include "image_transport/single_subscriber_publisher.hpp"
Expand Down Expand Up @@ -63,14 +65,58 @@ class PublisherPlugin
* \brief Advertise a topic, simple version.
*/
void advertise(
rclcpp::Node * nh,
rclcpp::Node::SharedPtr nh,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions())
{
advertiseImpl(nh, base_topic, custom_qos, options);
if (impl_) {
throw std::runtime_error("advertise has been called previously!");
}
impl_ = std::make_unique<Impl>();
impl_->node_ = nh;
advertise(base_topic, custom_qos, options);
}

void advertise(
rclcpp_lifecycle::LifecycleNode::SharedPtr nh,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions())
{
if (impl_) {
throw std::runtime_error("advertise has been called previously!");
}
impl_ = std::make_unique<Impl>();
impl_->lifecycle_node_ = nh;
advertise(base_topic, custom_qos, options);
}

void advertise(
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions())
{
advertiseImpl(base_topic, custom_qos, options);
}
Benjamin-Tan marked this conversation as resolved.
Show resolved Hide resolved

bool get_node(rclcpp::Node::SharedPtr & node) const
{
if (impl_ && impl_->node_) {
node = impl_->node_;
return true;
}
return false;
}

bool get_node(rclcpp_lifecycle::LifecycleNode::SharedPtr & node) const
{
if (impl_ && impl_->lifecycle_node_) {
node = impl_->lifecycle_node_;
return true;
}
return false;
}
/**
* \brief Returns the number of subscribers that are currently connected to
* this PublisherPlugin.
Expand Down Expand Up @@ -135,10 +181,18 @@ class PublisherPlugin
* \brief Advertise a topic. Must be implemented by the subclass.
*/
virtual void advertiseImpl(
rclcpp::Node * node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options) = 0;

private:
struct Impl
{
rclcpp::Node::SharedPtr node_;
rclcpp_lifecycle::LifecycleNode::SharedPtr lifecycle_node_;
};

std::unique_ptr<Impl> impl_;
};

} // namespace image_transport
Expand Down
Loading