Skip to content

Commit c9a6f6e

Browse files
committed
Now fully cover the area to fill with rectangles in the target image for depth_image_proc register when filling holes, eliminating the sliver effect from some angles (low angles will stil have them, would need to use depth values from adjacent pixels to avoid that)
1 parent 67762dd commit c9a6f6e

File tree

1 file changed

+43
-29
lines changed

1 file changed

+43
-29
lines changed

depth_image_proc/src/nodelets/register.cpp

Lines changed: 43 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -271,10 +271,11 @@ void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
271271
const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
272272
const int row_step = depth_msg->step / sizeof(T);
273273
T* registered_data = reinterpret_cast<T*>(&registered_msg->data[0]);
274-
int raw_index = 0;
274+
// TODO(lucasw) this isn't used
275+
// int raw_index = 0;
275276
for (unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
276277
{
277-
for (unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
278+
for (unsigned u = 0; u < depth_msg->width; ++u /* , ++raw_index */)
278279
{
279280
const T raw_depth = depth_row[u];
280281
if (!DepthTraits<T>::valid(raw_depth))
@@ -296,7 +297,7 @@ void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
296297
continue;
297298
}
298299

299-
T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
300+
T& reg_depth = registered_data[v_rgb*dst_width + u_rgb];
300301
// Validity and Z-buffer checks
301302
if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
302303
reg_depth = new_depth;
@@ -306,40 +307,53 @@ void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
306307
{
307308
// TODO(lucasw) loop on two -0.5, 0.5 vectors, keep track of u_min/max and v_min/max
308309
// as it goes
309-
int u_rgb_1;
310-
int v_rgb_1;
311-
T new_depth_1;
312-
if (!transform_depth(depth_to_rgb,
313-
u - 0.5, v - 0.5,
314-
depth_model_, rgb_model_,
315-
inv_depth_fx, inv_depth_fy,
316-
dst_width, dst_height,
317-
depth,
318-
u_rgb_1, v_rgb_1, new_depth_1)) {
319-
// TODO(lucasw) need to be able to handle partiall out of bounds squares here
320-
continue;
310+
int u_rgb_min, u_rgb_max;
311+
int v_rgb_min, v_rgb_max;
312+
size_t count = 0;
313+
T new_depth_sum = 0.0;
314+
const std::array<double, 2> uv_offsets = {-0.5, 0.5};
315+
for (const auto& v_offset : uv_offsets) {
316+
for (const auto& u_offset : uv_offsets) {
317+
int u_rgb;
318+
int v_rgb;
319+
T new_depth;
320+
if (!transform_depth(depth_to_rgb,
321+
u + u_offset, v + v_offset,
322+
depth_model_, rgb_model_,
323+
inv_depth_fx, inv_depth_fy,
324+
dst_width, dst_height,
325+
depth,
326+
u_rgb, v_rgb, new_depth)) {
327+
// TODO(lucasw) need to be able to handle partiall out of bounds squares here
328+
continue;
329+
}
330+
if (count == 0) {
331+
u_rgb_min = u_rgb;
332+
u_rgb_max = u_rgb;
333+
v_rgb_min = v_rgb;
334+
v_rgb_max = v_rgb;
335+
} else {
336+
u_rgb_min = std::min(u_rgb, u_rgb_min);
337+
u_rgb_max = std::max(u_rgb, u_rgb_max);
338+
v_rgb_min = std::min(v_rgb, v_rgb_min);
339+
v_rgb_max = std::max(v_rgb, v_rgb_max);
340+
}
341+
new_depth_sum += new_depth;
342+
count++;
343+
}
321344
}
322345

323-
int u_rgb_2;
324-
int v_rgb_2;
325-
T new_depth_2;
326-
if (!transform_depth(depth_to_rgb,
327-
u + 0.5, v + 0.5,
328-
depth_model_, rgb_model_,
329-
inv_depth_fx, inv_depth_fy,
330-
dst_width, dst_height,
331-
depth,
332-
u_rgb_2, v_rgb_2, new_depth_2)) {
346+
if (count == 0) {
333347
continue;
334348
}
335349

336350
// fill in the square defined by uv range
337-
const T new_depth = DepthTraits<T>::fromMeters(0.5 * (new_depth_1 + new_depth_2));
338-
for (int nv=std::min(v_rgb_1, v_rgb_2); nv<=std::max(v_rgb_1, v_rgb_2); ++nv)
351+
const T new_depth = DepthTraits<T>::fromMeters(new_depth_sum / static_cast<double>(count));
352+
for (int nv=v_rgb_min; nv<=v_rgb_max; ++nv)
339353
{
340-
for (int nu=std::min(u_rgb_1, u_rgb_2); nu<=std::max(u_rgb_2, u_rgb_2); ++nu)
354+
for (int nu=u_rgb_min; nu<=u_rgb_max; ++nu)
341355
{
342-
T& reg_depth = registered_data[nv*registered_msg->width + nu];
356+
T& reg_depth = registered_data[nv*dst_width + nu];
343357
// Validity and Z-buffer checks
344358
if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
345359
reg_depth = new_depth;

0 commit comments

Comments
 (0)