From a44c04d191a6854ffca01f90ef5d0791ec0b7bd1 Mon Sep 17 00:00:00 2001 From: Egor Bredikhin Date: Mon, 2 Nov 2020 11:03:06 -0500 Subject: [PATCH] Fix initialization order for _unit_step_size --- realsense2_camera/src/realsense_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/realsense2_camera/src/realsense_node.cpp b/realsense2_camera/src/realsense_node.cpp index f85dd409f0..f36b112e6c 100644 --- a/realsense2_camera/src/realsense_node.cpp +++ b/realsense2_camera/src/realsense_node.cpp @@ -28,9 +28,6 @@ RealSenseNode::RealSenseNode(const ros::NodeHandle &nodeHandle, _intialize_time_base(false), _namespace(getNamespaceStr()) { - getParameters(); - getDevice(); - // Types for depth stream _is_frame_arrived[DEPTH] = false; _format[DEPTH] = RS2_FORMAT_Z16; // libRS type @@ -91,6 +88,9 @@ RealSenseNode::RealSenseNode(const ros::NodeHandle &nodeHandle, _unit_step_size[ACCEL] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size _stream_name[ACCEL] = "accel"; + getParameters(); + getDevice(); + // TODO: Improve the pipeline to accept decimation filter // TODO: Provide disparity map if requested filters.emplace_back("Depth_to_Disparity", depth_to_disparity);