@@ -105,7 +105,7 @@ 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+ handleDepth (sample.depthFrame );
109109 break ;
110110 case ST::CaptureSessionSample::Type::VisibleFrame:
111111 ROS_INFO_THROTTLE (1.0 , " Visible frame: size %dx%d\n " , sample.visibleFrame .width (), sample.visibleFrame .height ());
@@ -123,7 +123,7 @@ struct SessionDelegate : ST::CaptureSessionDelegate {
123123 }
124124 if (sample.depthFrame .isValid ())
125125 {
126- handleDepth (sample.depthFrame );
126+ handleDepth (sample.depthFrame );
127127 }
128128 if (sample.infraredFrame .isValid ())
129129 {
@@ -351,6 +351,8 @@ class SCNode
351351
352352 bool imu_enable_;
353353
354+ bool depth_correction_enable_;
355+
354356 SessionDelegate *delegate_ = nullptr ;
355357 ST::CaptureSessionSettings sessionConfig_;
356358 ST::CaptureSession captureSession_;
@@ -374,6 +376,9 @@ class SCNode
374376 ros::param::param<bool >(" ~imu_enable" , imu_enable_, false );
375377 ROS_INFO_STREAM (NODE_NAME << " : imu_enable = " << imu_enable_);
376378
379+ ros::param::param<bool >(" ~depth_correction_enable" , depth_correction_enable_, false );
380+ ROS_INFO_STREAM (NODE_NAME << " : depth_correction_enable = " << depth_correction_enable_);
381+
377382 std::string frame_id;
378383 ros::param::param<std::string>(" ~frame_id" , frame_id, DEFAULT_FRAME_ID);
379384 ROS_INFO_STREAM (NODE_NAME << " : frame_id = " << frame_id);
@@ -393,6 +398,7 @@ class SCNode
393398
394399 sessionConfig_.source = ST::CaptureSessionSourceId::StructureCore;
395400 sessionConfig_.structureCore = scConfig;
401+ sessionConfig_.applyExpensiveCorrection = depth_correction_enable_;
396402
397403 delegate_ = new SessionDelegate (nh_, frame_id, sessionConfig_);
398404 captureSession_.setDelegate (delegate_);
0 commit comments