Skip to content

Commit

Permalink
renamed parameter to invalid_depth from default_depth
Browse files Browse the repository at this point in the history
  • Loading branch information
PhilippPolterauer committed Feb 17, 2024
1 parent c5b78f0 commit 079454e
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 20 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
*pyc
.vscode/
*/doc/generated
/build/
/log/
/install/
30 changes: 15 additions & 15 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 default_depth = 0.0)
double invalid_depth = 0.0)
{
// Use correct principal point from calibration
float center_x = model.cx();
Expand All @@ -64,18 +64,18 @@ void convertDepth(
float constant_x = unit_scaling / model.fx();
float constant_y = unit_scaling / model.fy();
float bad_point = std::numeric_limits<float>::quiet_NaN();
// the following lines ensure that the computation only happens in case we have a default depth
const T default_depth_cvt;
bool use_default_depth = default_depth != 0.0;
if (use_default_depth) {
default_depth_cvt=DepthTraits<T>::fromMeters(default_depth);

// 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: i think this is undefined behaviour we should favor memcpy? https://stackoverflow.com/questions/55150001/vector-with-reinterpret-cast
// TODO(philipppolterauer): i think this is undefined behaviour we should favor memcpy? https://stackoverflow.com/questions/55150001/vector-with-reinterpret-cast
const T * depth_row = reinterpret_cast<const T *>(&depth_msg->data[0]);
uint32_t row_step = depth_msg->step / sizeof(T);
for (uint32_t v = 0; v < cloud_msg->height; ++v, depth_row += row_step) {
Expand All @@ -84,8 +84,8 @@ void convertDepth(

// Missing points denoted by NaNs
if (!DepthTraits<T>::valid(depth)) {
if (use_default_depth) {
depth = default_depth_cvt;
if (use_invalid_depth) {
depth = invalid_depth_cvt;
} else {
*iter_x = *iter_y = *iter_z = bad_point;
continue;
Expand All @@ -104,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 @@ -137,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 @@ -153,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
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
6 changes: 3 additions & 3 deletions depth_image_proc/src/point_cloud_xyz.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,8 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options)
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);
invalid_depth_ = this->declare_parameter<double>("invalid_depth", 0.0);

// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
Expand Down Expand Up @@ -97,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 Down

0 comments on commit 079454e

Please sign in to comment.