@@ -105,7 +105,16 @@ struct SessionDelegate : ST::CaptureSessionDelegate {
105105 switch (sample.type ) {
106106 case ST::CaptureSessionSample::Type::DepthFrame:
107107 ROS_INFO_THROTTLE (1.0 , " Depth frame: size %dx%d\n " , sample.depthFrame .width (), sample.depthFrame .height ());
108- handleDepth (sample.depthFrame );
108+ if (depth_correction_enable_)
109+ {
110+ ST::DepthFrame x = sample.depthFrame ;
111+ x.applyExpensiveCorrection ();
112+ handleDepth (x);
113+ }
114+ else
115+ {
116+ handleDepth (sample.depthFrame );
117+ }
109118 break ;
110119 case ST::CaptureSessionSample::Type::VisibleFrame:
111120 ROS_INFO_THROTTLE (1.0 , " Visible frame: size %dx%d\n " , sample.visibleFrame .width (), sample.visibleFrame .height ());
@@ -123,7 +132,16 @@ struct SessionDelegate : ST::CaptureSessionDelegate {
123132 }
124133 if (sample.depthFrame .isValid ())
125134 {
126- handleDepth (sample.depthFrame );
135+ if (depth_correction_enable_)
136+ {
137+ ST::DepthFrame x = sample.depthFrame ;
138+ x.applyExpensiveCorrection ();
139+ handleDepth (x);
140+ }
141+ else
142+ {
143+ handleDepth (sample.depthFrame ;
144+ }
127145 }
128146 if (sample.infraredFrame .isValid ())
129147 {
@@ -351,6 +369,8 @@ class SCNode
351369
352370 bool imu_enable_;
353371
372+ bool depth_correction_enable_;
373+
354374 SessionDelegate *delegate_ = nullptr ;
355375 ST::CaptureSessionSettings sessionConfig_;
356376 ST::CaptureSession captureSession_;
@@ -374,6 +394,9 @@ class SCNode
374394 ros::param::param<bool >(" ~imu_enable" , imu_enable_, false );
375395 ROS_INFO_STREAM (NODE_NAME << " : imu_enable = " << imu_enable_);
376396
397+ ros::param::param<bool >(" ~depth_correction_enable" , depth_correction_enable_, false );
398+ ROS_INFO_STREAM (NODE_NAME << " : depth_correction_enable = " << depth_correction_enable_);
399+
377400 std::string frame_id;
378401 ros::param::param<std::string>(" ~frame_id" , frame_id, DEFAULT_FRAME_ID);
379402 ROS_INFO_STREAM (NODE_NAME << " : frame_id = " << frame_id);
0 commit comments