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 9 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()
26 changes: 22 additions & 4 deletions image_transport/default_plugins.xml
Original file line number Diff line number Diff line change
@@ -1,17 +1,35 @@
<library path="image_transport_plugins">
<class
name="image_transport/raw_pub"
type="image_transport::RawPublisher"
base_class_type="image_transport::PublisherPlugin">
type="image_transport::RawPublisher&lt;rclcpp::Node&gt;"
base_class_type="image_transport::PublisherPlugin&lt;rclcpp::Node&gt;">
<description>
This is the default publisher. It publishes the Image as-is on the base topic.
</description>
</class>

<class
name="image_transport/raw_lifecycle_pub"
type="image_transport::RawPublisher&lt;rclcpp_lifecycle::LifecycleNode&gt;"
base_class_type="image_transport::PublisherPlugin&lt;rclcpp_lifecycle::LifecycleNode&gt;">
<description>
This is the default publisher. It publishes the Image as-is on the base topic.
</description>
</class>

<class
name="image_transport/raw_sub"
type="image_transport::RawSubscriber"
base_class_type="image_transport::SubscriberPlugin">
type="image_transport::RawSubscriber&lt;rclcpp::Node&gt;"
base_class_type="image_transport::SubscriberPlugin&lt;rclcpp::Node&gt;">
<description>
This is the default pass-through subscriber for topics of type sensor_msgs/Image.
</description>
</class>

<class
name="image_transport/raw_lifecycle_sub"
type="image_transport::RawSubscriber&lt;rclcpp_lifecycle::LifecycleNode&gt;"
base_class_type="image_transport::SubscriberPlugin&lt;rclcpp_lifecycle::LifecycleNode&gt;">
<description>
This is the default pass-through subscriber for topics of type sensor_msgs/Image.
</description>
Expand Down
19 changes: 15 additions & 4 deletions 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 All @@ -43,9 +44,6 @@

namespace image_transport
{

class ImageTransport;

/**
* \brief Manages advertisements for publishing camera images.
*
Expand All @@ -61,6 +59,7 @@ class ImageTransport;
* associated with that handle will stop being called. Once all CameraPublisher for a
* given base topic go out of scope the topic (and all subtopics) will be unadvertised.
*/
template<class NodeType = rclcpp::Node>
class CameraPublisher
{
public:
Expand All @@ -69,7 +68,14 @@ class CameraPublisher

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

IMAGE_TRANSPORT_PUBLIC
CameraPublisher(
std::shared_ptr<NodeType> 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 +148,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
21 changes: 17 additions & 4 deletions 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 All @@ -42,9 +43,6 @@

namespace image_transport
{

class ImageTransport;

/**
* \brief Manages a subscription callback on synchronized Image and CameraInfo topics.
*
Expand All @@ -60,6 +58,7 @@ void callback(const sensor_msgs::msg::Image::ConstSharedPtr&, const sensor_msgs:
* associated with that handle will stop being called. Once all CameraSubscriber for a given
* topic go out of scope the topic will be unsubscribed.
*/
template<class NodeType = rclcpp::Node>
class CameraSubscriber
{
public:
Expand All @@ -71,7 +70,15 @@ class CameraSubscriber

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber(
rclcpp::Node * node,
NodeType * 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(
std::shared_ptr<NodeType> node,
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
Expand Down Expand Up @@ -120,6 +127,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
Loading