diff --git a/realsense_ros/CMakeLists.txt b/realsense_ros/CMakeLists.txt index 1b2b885..07d4801 100644 --- a/realsense_ros/CMakeLists.txt +++ b/realsense_ros/CMakeLists.txt @@ -65,6 +65,7 @@ set(CMAKE_CXX_FLAGS "-fPIE -fPIC -D_FORTIFY_SOURCE=2 -fstack-protector -Wformat # find dependencies find_package(ament_cmake REQUIRED) +find_package(rcl REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(nav_msgs REQUIRED) @@ -100,6 +101,7 @@ target_link_libraries(${PROJECT_NAME} ) ament_target_dependencies(${PROJECT_NAME} + rcl rclcpp rclcpp_components nav_msgs @@ -133,6 +135,7 @@ install( if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) + find_package(rcl REQUIRED) find_package(rclcpp REQUIRED) find_package(nav_msgs REQUIRED) find_package(sensor_msgs REQUIRED) @@ -162,6 +165,7 @@ if(BUILD_TESTING) realsense2 ${PROJECT_NAME}) ament_target_dependencies(${target} + "rcl" "rclcpp" "nav_msgs" "sensor_msgs" diff --git a/realsense_ros/include/realsense/rs_base.hpp b/realsense_ros/include/realsense/rs_base.hpp index ecd5381..1d05b12 100644 --- a/realsense_ros/include/realsense/rs_base.hpp +++ b/realsense_ros/include/realsense/rs_base.hpp @@ -80,6 +80,7 @@ class RealSenseBase Result toggleStream(const stream_index_pair & stream, const rclcpp::Parameter & param); Result changeResolution(const stream_index_pair & stream, const rclcpp::Parameter & param); Result changeFPS(const stream_index_pair & stream, const rclcpp::Parameter & param); + rclcpp::Time frameToTime(const rs2::frame & frame); typedef struct VideoStreamInfo { diff --git a/realsense_ros/package.xml b/realsense_ros/package.xml index a85f0b7..cae4d0c 100644 --- a/realsense_ros/package.xml +++ b/realsense_ros/package.xml @@ -21,6 +21,8 @@ realsense_msgs image_transport + rcl + launch_ros ament_lint_auto diff --git a/realsense_ros/src/rs_base.cpp b/realsense_ros/src/rs_base.cpp index 355f978..b47bf90 100644 --- a/realsense_ros/src/rs_base.cpp +++ b/realsense_ros/src/rs_base.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include "rcl/time.h" #include "realsense/rs_base.hpp" namespace realsense @@ -457,4 +458,8 @@ Result RealSenseBase::changeFPS(const stream_index_pair & stream, const rclcpp:: } return result; } + +rclcpp::Time RealSenseBase::frameToTime(const rs2::frame & frame) { + return rclcpp::Time(RCL_MS_TO_NS(frame.get_timestamp())); +} } // namespace realsense diff --git a/realsense_ros/src/rs_d435.cpp b/realsense_ros/src/rs_d435.cpp index bcd8786..0d2a202 100644 --- a/realsense_ros/src/rs_d435.cpp +++ b/realsense_ros/src/rs_d435.cpp @@ -60,7 +60,7 @@ RealSenseD435::RealSenseD435(rs2::context ctx, rs2::device dev, rclcpp::Node & n void RealSenseD435::publishTopicsCallback(const rs2::frame & frame) { rs2::frameset frameset = frame.as(); - rclcpp::Time t = node_.now(); + rclcpp::Time t = frameToTime(frame); if (enable_[COLOR] && (image_pub_[COLOR]->get_subscription_count() > 0 || camera_info_pub_[COLOR]->get_subscription_count() > 0)){ auto frame = frameset.get_color_frame(); publishImageTopic(frame, t); diff --git a/realsense_ros/src/rs_d435i.cpp b/realsense_ros/src/rs_d435i.cpp index b452de2..a2b1662 100644 --- a/realsense_ros/src/rs_d435i.cpp +++ b/realsense_ros/src/rs_d435i.cpp @@ -35,7 +35,7 @@ RealSenseD435I::RealSenseD435I(rs2::context ctx, rs2::device dev, rclcpp::Node & void RealSenseD435I::publishTopicsCallback(const rs2::frame & frame) { - rclcpp::Time t = node_.now(); + rclcpp::Time t = frameToTime(frame); if (frame.is()) { RealSenseD435::publishTopicsCallback(frame); } else if (frame.is()) { diff --git a/realsense_ros/src/rs_t265.cpp b/realsense_ros/src/rs_t265.cpp index a44b30f..bde3b1a 100644 --- a/realsense_ros/src/rs_t265.cpp +++ b/realsense_ros/src/rs_t265.cpp @@ -42,7 +42,7 @@ RealSenseT265::RealSenseT265(rs2::context ctx, rs2::device dev, rclcpp::Node & n void RealSenseT265::publishTopicsCallback(const rs2::frame & frame) { - rclcpp::Time t = node_.now(); + rclcpp::Time t = frameToTime(frame); if (frame.is()) { auto frameset = frame.as();