Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
Prev Previous commit
Next Next commit
Add lifecycle node dependency
  • Loading branch information
ashrafk93 committed Mar 19, 2025
commit 09e9f8eed2b4e28c0c20a20042486e7caed7b7cf
46 changes: 45 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
* [ROS1 and ROS2 legacy](#ros1-and-ros2-legacy)
* [Installation on Ubuntu](#installation-on-ubuntu)
* [Installation on Windows](#installation-on-windows)
* [ROS2 LifeCycleNode](#ros2-lifecyclenode)
* [Usage](#usage)
* [Starting the camera node](#start-the-camera-node)
* [Camera name and namespace](#camera-name-and-camera-namespace)
Expand Down Expand Up @@ -247,6 +248,49 @@
<hr>



# ROS2 LifeCycleNode

The `USE_LIFECYCLE_NODES` cmake flag enables **ROS2 Lifecycle Nodes** (`rclcpp_lifecycle::LifecycleNode`) in the **Realsense SDK**, providing better node management and explicit state transitions.

However, enabling this flag introduces a limitation where **Image Transport functionality (`image_transport`) is** <span style="color:#ff6666">**disabled**</span> **when `USE_LIFECYCLE_NODES=ON`**.
This means that **compressed image topics (e.g., JPEG, PNG, Theora) will not be available** and<br>
**Subscribers** must use raw image topics, which may increase bandwidth usage.

> Note: Users who do not depend on image_transport will not be affected by this change and can safely enable Lifecycle Nodes without any impact on their workflow.

### 📌 Why Does This Limitation Exist?
The `image_transport` package does **not support Lifecycle Nodes** (`rclcpp_lifecycle::LifecycleNode`).
This is a known issue in the ROS community, and you can find more details in the discussion here:
🔗 [ROS2 `image_transport` does not support Lifecycle Nodes](https://github.com/ros-perception/image_common/issues/108).

Since `image_transport::create_publisher()` requires an `rclcpp::Node`, but **Lifecycle Nodes do not inherit from `rclcpp::Node` directly**, `image_transport` cannot be used in a lifecycle-based architecture.

To build the SDK with Lifecycle Nodes enabled:
```bash
colcon build --cmake-args -DUSE_LIFECYCLE_NODES=ON
```

To use standard ROS2 nodes **(default behavior)** and retain image_transport functionality:
```bash
colcon build --cmake-args -DUSE_LIFECYCLE_NODES=OFF
```

### Lifecycle State Transitions
The RealSense node follows the ROS2 managed lifecycle. Below is a breakdown of each state and the corresponding function calls:

| **State** | **Transition Function** | **Description** |
|-------------------|-----------------------------|-----------------|
| `UNCONFIGURED` | **Node Created** | The node is instantiated but not initialized. |
| `CONFIGURING` | `on_configure()` → `init()` | Initializes parameters and attempts to discover the RealSense device. |
| `INACTIVE` | - | The node is initialized but not yet publishing data. |
| `ACTIVATING` | `on_activate()` → `startDevice()` | Starts the RealSense device and begins publishing topics. |
| `ACTIVE` | - | The node is fully operational and publishing data. |
| `DEACTIVATING` | `on_deactivate()` → `stopDevice()` | Stops publishing but retains device configuration. |
| `CLEANUP` | `on_cleanup()` → `closeDevice()` | Resets all resources, allowing reconfiguration. |
| `SHUTDOWN` | `on_shutdown()` → `closeDevice()` | Cleans up before process termination (doesnt actually terminate the process itself due to ROS2 composable nodes and component manager ) |
<hr>

# Usage

## Start the camera node
Expand All @@ -257,9 +301,9 @@
ros2 run realsense2_camera realsense2_camera_node --ros-args -p enable_color:=false -p spatial_filter.enable:=true -p temporal_filter.enable:=true

#### with ros2 launch:
export USE_LIFECYCLE_NODES=true/false # default is false
ros2 launch realsense2_camera rs_launch.py
ros2 launch realsense2_camera rs_launch.py depth_module.depth_profile:=1280x720x30 pointcloud.enable:=true

<hr>

## Camera Name And Camera Namespace
Expand Down
14 changes: 14 additions & 0 deletions realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()
option(BUILD_WITH_OPENMP "Use OpenMP" OFF)
option(SET_USER_BREAK_AT_STARTUP "Set user wait point in startup (for debug)" OFF)
# Define an option to enable or disable lifecycle nodes
option(USE_LIFECYCLE_NODES "Enable lifecycle nodes (ON/OFF)" OFF)

# Compiler Defense Flags
if(UNIX OR APPLE)
Expand Down Expand Up @@ -107,6 +109,8 @@ find_package(builtin_interfaces REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(image_transport REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(realsense2_camera_msgs REQUIRED)
Expand Down Expand Up @@ -198,6 +202,14 @@ if (BUILD_ACCELERATE_GPU_WITH_GLSL)
add_definitions(-DACCELERATE_GPU_WITH_GLSL)
endif()

# If the flag is enabled, define the macro
if(USE_LIFECYCLE_NODES)
add_definitions(-DUSE_LIFECYCLE_NODES)
message("🚀 USE_LIFECYCLE_NODES is ENABLED")
else()
message("❌ USE_LIFECYCLE_NODES is DISABLED")
endif()

set(INCLUDES
include/constants.h
include/realsense_node_factory.h
Expand Down Expand Up @@ -248,6 +260,8 @@ set(dependencies
cv_bridge
image_transport
rclcpp
rclcpp_lifecycle
lifecycle_msgs
rclcpp_components
realsense2_camera_msgs
std_srvs
Expand Down
4 changes: 2 additions & 2 deletions realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ namespace realsense2_camera
class BaseRealSenseNode
{
public:
BaseRealSenseNode(rclcpp::Node& node,
BaseRealSenseNode(RosNodeBase& node,
rs2::device dev,
std::shared_ptr<Parameters> parameters,
bool use_intra_process = false);
Expand Down Expand Up @@ -154,7 +154,7 @@ namespace realsense2_camera

std::string _base_frame_id;
bool _is_running;
rclcpp::Node& _node;
RosNodeBase& _node;
std::string _camera_name;
std::vector<rs2_option> _monitor_options;
rclcpp::Logger _logger;
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/include/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#pragma once

#include <string>
#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"

#define REALSENSE_ROS_MAJOR_VERSION 4
#define REALSENSE_ROS_MINOR_VERSION 55
Expand Down
4 changes: 2 additions & 2 deletions realsense2_camera/include/dynamic_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ namespace realsense2_camera
class Parameters
{
public:
Parameters(rclcpp::Node& node);
Parameters(RosNodeBase& node);
~Parameters();
template <class T>
T setParam(std::string param_name, const T& initial_value,
Expand Down Expand Up @@ -54,7 +54,7 @@ namespace realsense2_camera
void monitor_update_functions();

private:
rclcpp::Node& _node;
RosNodeBase& _node;
rclcpp::Logger _logger;
std::map<std::string, std::function<void(const rclcpp::Parameter&)> > _param_functions;
std::map<void*, std::string> _param_names;
Expand Down
4 changes: 2 additions & 2 deletions realsense2_camera/include/image_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#pragma once

#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"
#include <sensor_msgs/msg/image.hpp>

#include <image_transport/image_transport.hpp>
Expand All @@ -32,7 +32,7 @@ class image_publisher
class image_rcl_publisher : public image_publisher
{
public:
image_rcl_publisher( rclcpp::Node & node,
image_rcl_publisher( RosNodeBase & node,
const std::string & topic_name,
const rmw_qos_profile_t & qos );
void publish( sensor_msgs::msg::Image::UniquePtr image_ptr ) override;
Expand Down
4 changes: 2 additions & 2 deletions realsense2_camera/include/pointcloud_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace realsense2_camera
class PointcloudFilter : public NamedFilter
{
public:
PointcloudFilter(std::shared_ptr<rs2::filter> filter, rclcpp::Node& node, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled=false);
PointcloudFilter(std::shared_ptr<rs2::filter> filter, RosNodeBase& node, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled=false);

void setPublisher();
void Publish(rs2::points pc, const rclcpp::Time& t, const rs2::frameset& frameset, const std::string& frame_id);
Expand All @@ -37,7 +37,7 @@ namespace realsense2_camera

private:
bool _is_enabled_pc;
rclcpp::Node& _node;
RosNodeBase& _node;
bool _allow_no_texture_points;
bool _ordered_pc;
std::mutex _mutex_publisher;
Expand Down
20 changes: 17 additions & 3 deletions realsense2_camera/include/realsense_node_factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
#include "base_realsense_node.h"
#include <builtin_interfaces/msg/time.hpp>
#include <console_bridge/console.h>
#include <rclcpp/rclcpp.hpp>
#include "rclcpp_components/register_node_macro.hpp"
#include "ros_node_base.h"
#include <algorithm>
#include <csignal>
#include <iostream>
Expand All @@ -34,25 +34,39 @@

namespace realsense2_camera
{
class RealSenseNodeFactory : public rclcpp::Node
class RealSenseNodeFactory : public RosNodeBase
{
public:

explicit RealSenseNodeFactory(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());
RealSenseNodeFactory(
const std::string & node_name, const std::string & ns,
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());
virtual ~RealSenseNodeFactory();
#ifdef USE_LIFECYCLE_NODES
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
#endif

private:

template<typename T>
T declareSafeParameter(const std::string& param_name, const T& default_value);

void init();
void closeDevice();
void startDevice();
void stopDevice();
void changeDeviceCallback(rs2::event_information& info);
void getDevice(rs2::device_list list);
void tryGetLogSeverity(rs2_log_severity& severity) const;
static std::string parseUsbPort(std::string line);

rclcpp::Node::SharedPtr _node;
RosNodeBase::SharedPtr _node;
rs2::device _device;
std::unique_ptr<BaseRealSenseNode> _realSenseNode;
rs2::context _ctx;
Expand Down
17 changes: 17 additions & 0 deletions realsense2_camera/include/ros_node_base.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
#ifndef ROS_NODE_BASE_HPP
#define ROS_NODE_BASE_HPP

#include <rclcpp/rclcpp.hpp>

#ifdef USE_LIFECYCLE_NODES
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#endif

// 🚀 Define RosNodeBase Alias
#ifdef USE_LIFECYCLE_NODES
using RosNodeBase = rclcpp_lifecycle::LifecycleNode;
#else
using RosNodeBase = rclcpp::Node;
#endif

#endif // ROS_NODE_BASE_HPP
6 changes: 3 additions & 3 deletions realsense2_camera/include/ros_param_backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

#pragma once

#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"

namespace realsense2_camera
{
class ParametersBackend
{
public:
ParametersBackend(rclcpp::Node& node) :
ParametersBackend(RosNodeBase& node) :
_node(node),
_logger(node.get_logger())
{}
Expand All @@ -38,7 +38,7 @@ namespace realsense2_camera


private:
rclcpp::Node& _node;
RosNodeBase& _node;
rclcpp::Logger _logger;
std::shared_ptr<void> _ros_callback;
};
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/include/ros_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <librealsense2/rsutil.h>
#include "constants.h"
#include <map>
#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"
#include <ros_utils.h>
#include <sensor_params.h>
#include <profile_manager.h>
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/include/ros_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <iostream>
#include <vector>
#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"
#include <librealsense2/rs.hpp>
#include <librealsense2/rsutil.h>

Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/include/sensor_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#pragma once
#include <librealsense2/rs.hpp>
#include <rclcpp/rclcpp.hpp>
#include "ros_node_base.h"
#include <dynamic_params.h>

namespace realsense2_camera
Expand Down
13 changes: 10 additions & 3 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,9 @@
import yaml
from launch import LaunchDescription
import launch_ros.actions
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.actions import DeclareLaunchArgument, OpaqueFunction, LogInfo
from launch.substitutions import LaunchConfiguration


configurable_parameters = [{'name': 'camera_name', 'default': 'camera', 'description': 'camera unique name'},
{'name': 'camera_namespace', 'default': 'camera', 'description': 'namespace for camera'},
{'name': 'serial_no', 'default': "''", 'description': 'choose device by serial number'},
Expand Down Expand Up @@ -107,15 +106,23 @@ def launch_setup(context, params, param_name_suffix=''):
_config_file = LaunchConfiguration('config_file' + param_name_suffix).perform(context)
params_from_file = {} if _config_file == "''" else yaml_to_dict(_config_file)

use_lifecycle_nodes = os.getenv('USE_LIFECYCLE_NODES', 'false').lower() == 'true'

_output = LaunchConfiguration('output' + param_name_suffix)

# Dynamically choose Node or LifecycleNode
node_action = launch_ros.actions.LifecycleNode if use_lifecycle_nodes else launch_ros.actions.Node
log_message = "Launching as LifecycleNode" if use_lifecycle_nodes else "Launching as Normal ROS Node"

if(os.getenv('ROS_DISTRO') == 'foxy'):
# Foxy doesn't support output as substitution object (LaunchConfiguration object)
# but supports it as string, so we fetch the string from this substitution object
# see related PR that was merged for humble, iron, rolling: https://github.com/ros2/launch/pull/577
_output = context.perform_substitution(_output)

return [
launch_ros.actions.Node(
LogInfo(msg=f"🚀 {log_message}"),
node_action(
package='realsense2_camera',
namespace=LaunchConfiguration('camera_namespace' + param_name_suffix),
name=LaunchConfiguration('camera_name' + param_name_suffix),
Expand Down
12 changes: 9 additions & 3 deletions realsense2_camera/launch/rs_multi_camera_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,11 @@
import copy
from launch import LaunchDescription, LaunchContext
import launch_ros.actions
from launch.actions import IncludeLaunchDescription, OpaqueFunction
from launch.actions import IncludeLaunchDescription, OpaqueFunction, LogInfo
from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
from launch.launch_description_sources import PythonLaunchDescriptionSource
import sys
import os
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.absolute()))
import rs_launch
Expand All @@ -50,15 +51,20 @@ def duplicate_params(general_params, posix):
return local_params

def launch_static_transform_publisher_node(context : LaunchContext):
# Dynamically choose Node or LifecycleNode
use_lifecycle_nodes = os.getenv('USE_LIFECYCLE_NODES', 'false').lower() == 'true'
node_action = launch_ros.actions.LifecycleNode if use_lifecycle_nodes else launch_ros.actions.Node
log_message = "Launching as LifecycleNode" if use_lifecycle_nodes else "Launching as Normal ROS Node"

# dummy static transformation from camera1 to camera2
node = launch_ros.actions.Node(
node = node_action(
package = "tf2_ros",
executable = "static_transform_publisher",
arguments = ["0", "0", "0", "0", "0", "0",
context.launch_configurations['camera_name1'] + "_link",
context.launch_configurations['camera_name2'] + "_link"]
)
return [node]
return [LogInfo(msg=f"🚀 {log_message}"), node]

def generate_launch_description():
params1 = duplicate_params(rs_launch.configurable_parameters, '1')
Expand Down
Loading