Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

924 introduce default depth param #943

Merged
Show file tree
Hide file tree
Changes from 2 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
5 changes: 4 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
*pyc
.vscode/settings.json
.vscode/
*/doc/generated
/build/
/log/
/install/
PhilippPolterauer marked this conversation as resolved.
Show resolved Hide resolved
30 changes: 19 additions & 11 deletions depth_image_proc/include/depth_image_proc/conversions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,9 @@ namespace depth_image_proc
template<typename T>
void convertDepth(
const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const image_geometry::PinholeCameraModel & model,
double range_max = 0.0)
double invalid_depth = 0.0)
mikeferguson marked this conversation as resolved.
Show resolved Hide resolved
{
// Use correct principal point from calibration
float center_x = model.cx();
Expand All @@ -65,19 +65,27 @@ void convertDepth(
float constant_y = unit_scaling / model.fy();
float bad_point = std::numeric_limits<float>::quiet_NaN();

// ensure that the computation only happens in case we have a default depth
T invalid_depth_cvt = T(0);
bool use_invalid_depth = invalid_depth != 0.0;
if (use_invalid_depth) {
invalid_depth_cvt = DepthTraits<T>::fromMeters(invalid_depth);
}
sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud_msg, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud_msg, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud_msg, "z");

// TODO(philipppolterauer): i think this is undefined behaviour we should favor memcpy? https://stackoverflow.com/questions/55150001/vector-with-reinterpret-cast
PhilippPolterauer marked this conversation as resolved.
Show resolved Hide resolved
const T * depth_row = reinterpret_cast<const T *>(&depth_msg->data[0]);
int row_step = depth_msg->step / sizeof(T);
for (int v = 0; v < static_cast<int>(cloud_msg->height); ++v, depth_row += row_step) {
for (int u = 0; u < static_cast<int>(cloud_msg->width); ++u, ++iter_x, ++iter_y, ++iter_z) {
uint32_t row_step = depth_msg->step / sizeof(T);
for (uint32_t v = 0; v < cloud_msg->height; ++v, depth_row += row_step) {
for (uint32_t u = 0; u < cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z) {
T depth = depth_row[u];

// Missing points denoted by NaNs
if (!DepthTraits<T>::valid(depth)) {
if (range_max != 0.0) {
depth = DepthTraits<T>::fromMeters(range_max);
if (use_invalid_depth) {
depth = invalid_depth_cvt;
mikeferguson marked this conversation as resolved.
Show resolved Hide resolved
} else {
*iter_x = *iter_y = *iter_z = bad_point;
continue;
Expand All @@ -96,8 +104,8 @@ void convertDepth(
template<typename T>
void convertDepthRadial(
const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
cv::Mat & transform)
const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const cv::Mat & transform)
{
// Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
float bad_point = std::numeric_limits<float>::quiet_NaN();
Expand Down Expand Up @@ -129,7 +137,7 @@ void convertDepthRadial(
template<typename T>
void convertIntensity(
const sensor_msgs::msg::Image::ConstSharedPtr & intensity_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg)
const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg)
{
sensor_msgs::PointCloud2Iterator<float> iter_i(*cloud_msg, "intensity");
const T * inten_row = reinterpret_cast<const T *>(&intensity_msg->data[0]);
Expand All @@ -145,7 +153,7 @@ void convertIntensity(
// Handles RGB8, BGR8, and MONO8
void convertRgb(
const sensor_msgs::msg::Image::ConstSharedPtr & rgb_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
sensor_msgs::msg::PointCloud2::SharedPtr cloud_msg,
int red_offset, int green_offset, int blue_offset, int color_step);

cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial);
Expand Down
3 changes: 3 additions & 0 deletions depth_image_proc/include/depth_image_proc/point_cloud_xyz.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ class PointCloudXyzNode : public rclcpp::Node
image_transport::CameraSubscriber sub_depth_;
int queue_size_;

// Parameters
double invalid_depth_;

// Publications
std::mutex connect_mutex_;
rclcpp::Publisher<PointCloud2>::SharedPtr pub_point_cloud_;
Expand Down
4 changes: 2 additions & 2 deletions depth_image_proc/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ cv::Mat initMatrix(

void convertRgb(
const sensor_msgs::msg::Image::ConstSharedPtr & rgb_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
int red_offset, int green_offset, int blue_offset, int color_step)
{
sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(*cloud_msg, "r");
Expand All @@ -101,7 +101,7 @@ void convertRgb(
// force template instantiation
template void convertDepth<uint16_t>(
const sensor_msgs::msg::Image::ConstSharedPtr & depth_msg,
sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const sensor_msgs::msg::PointCloud2::SharedPtr & cloud_msg,
const image_geometry::PinholeCameraModel & model,
double range_max);

Expand Down
9 changes: 6 additions & 3 deletions depth_image_proc/src/point_cloud_xyz.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,9 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options)
// Read parameters
queue_size_ = this->declare_parameter<int>("queue_size", 5);

// values used for invalid points for pcd conversion
invalid_depth_ = this->declare_parameter<double>("invalid_depth", 0.0);
PhilippPolterauer marked this conversation as resolved.
Show resolved Hide resolved

// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
Expand Down Expand Up @@ -94,7 +97,7 @@ void PointCloudXyzNode::depthCb(
const Image::ConstSharedPtr & depth_msg,
const CameraInfo::ConstSharedPtr & info_msg)
{
auto cloud_msg = std::make_shared<PointCloud2>();
const PointCloud2::SharedPtr cloud_msg = std::make_shared<PointCloud2>();
cloud_msg->header = depth_msg->header;
cloud_msg->height = depth_msg->height;
cloud_msg->width = depth_msg->width;
Expand All @@ -109,9 +112,9 @@ void PointCloudXyzNode::depthCb(

// Convert Depth Image to Pointcloud
if (depth_msg->encoding == enc::TYPE_16UC1 || depth_msg->encoding == enc::MONO16) {
convertDepth<uint16_t>(depth_msg, cloud_msg, model_);
convertDepth<uint16_t>(depth_msg, cloud_msg, model_, invalid_depth_);
} else if (depth_msg->encoding == enc::TYPE_32FC1) {
convertDepth<float>(depth_msg, cloud_msg, model_);
convertDepth<float>(depth_msg, cloud_msg, model_, invalid_depth_);
} else {
RCLCPP_ERROR(
get_logger(), "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
Expand Down