Skip to content
Open
Changes from all commits
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
8 changes: 7 additions & 1 deletion src/sc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ struct SessionDelegate : ST::CaptureSessionDelegate {
for(int x = 0; x < depthFrame.width(); x++)
{
std::size_t pixelOffset = (y * depthFrame.width()) + x;
img.at<float>(y, x) = buf[pixelOffset];
img.at<float>(y, x) = buf[pixelOffset] * 0.001f;
}
}

Expand Down Expand Up @@ -351,6 +351,8 @@ class SCNode

bool imu_enable_;

bool depth_correction_enable_;

SessionDelegate *delegate_ = nullptr;
ST::CaptureSessionSettings sessionConfig_;
ST::CaptureSession captureSession_;
Expand All @@ -374,6 +376,9 @@ class SCNode
ros::param::param<bool>("~imu_enable", imu_enable_, false);
ROS_INFO_STREAM(NODE_NAME << ": imu_enable = " << imu_enable_);

ros::param::param<bool>("~depth_correction_enable", depth_correction_enable_, false);
ROS_INFO_STREAM(NODE_NAME << ": depth_correction_enable = " << depth_correction_enable_);

std::string frame_id;
ros::param::param<std::string>("~frame_id", frame_id, DEFAULT_FRAME_ID);
ROS_INFO_STREAM(NODE_NAME << ": frame_id = " << frame_id);
Expand All @@ -393,6 +398,7 @@ class SCNode

sessionConfig_.source = ST::CaptureSessionSourceId::StructureCore;
sessionConfig_.structureCore = scConfig;
sessionConfig_.applyExpensiveCorrection = depth_correction_enable_;

delegate_ = new SessionDelegate(nh_, frame_id, sessionConfig_);
captureSession_.setDelegate(delegate_);
Expand Down