Skip to content

Commit b303b75

Browse files
committed
factored out common code from depth_image_proc register convert
1 parent ac8c09d commit b303b75

File tree

1 file changed

+88
-61
lines changed

1 file changed

+88
-61
lines changed

depth_image_proc/src/nodelets/register.cpp

Lines changed: 88 additions & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -195,6 +195,53 @@ void RegisterNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
195195
pub_registered_.publish(registered_msg, registered_info_msg);
196196
}
197197

198+
template<typename T>
199+
bool transform_depth(
200+
const Eigen::Affine3d& depth_to_rgb,
201+
const double u, const double v,
202+
const image_geometry::PinholeCameraModel& depth_model_,
203+
const image_geometry::PinholeCameraModel& rgb_model_,
204+
const double inv_depth_fx, const double inv_depth_fy,
205+
const int width, const int height,
206+
const double depth,
207+
int& u_rgb, int& v_rgb,
208+
T& new_depth)
209+
{
210+
// TODO(lucasw) pulling these out shouldn't cost anything
211+
const auto depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
212+
const auto depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
213+
const auto rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
214+
const auto rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
215+
const auto rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
216+
217+
/// @todo Combine all operations into one matrix multiply on (u,v,d)
218+
// Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
219+
Eigen::Vector4d xyz_depth;
220+
xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
221+
((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
222+
depth,
223+
1;
224+
225+
// Transform to RGB camera frame
226+
Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
227+
// TODO(lucasw) return false if xyz_rgb.z() < 0.0 - or is that okay for some < 0 fx/fy?
228+
229+
// Project to (u,v) in RGB image
230+
const double inv_Z = 1.0 / xyz_rgb.z();
231+
232+
u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
233+
if (u_rgb < 0 || u_rgb >= width)
234+
return false;
235+
236+
v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
237+
if (v_rgb < 0 || v_rgb >= height)
238+
return false;
239+
240+
new_depth = static_cast<T>(xyz_rgb.z());
241+
242+
return true;
243+
}
244+
198245
// TODO(lucasw) need a unit test for this, simple low res image (e.g. 4x4 pixels) with
199246
// depth ranges of around 1.0
200247
// shift it to the right 1.0 units, view from 90 degrees
@@ -212,12 +259,10 @@ void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
212259
// Extract all the parameters we need
213260
const double inv_depth_fx = 1.0 / depth_model_.fx();
214261
const double inv_depth_fy = 1.0 / depth_model_.fy();
215-
const double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
216-
const double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
217-
const double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
218-
const double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
219-
const double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
220-
262+
263+
const int dst_width = static_cast<int>(registered_msg->width);
264+
const int dst_height = static_cast<int>(registered_msg->height);
265+
221266
// Transform the depth values into the RGB frame
222267
/// @todo When RGB is higher res, interpolate by rasterizing depth triangles onto the registered image
223268
const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
@@ -236,75 +281,57 @@ void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
236281

237282
if (fill_upsampling_holes_ == false)
238283
{
239-
// TODO(lucasw) factor out common code below
240-
/// @todo Combine all operations into one matrix multiply on (u,v,d)
241-
// Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
242-
Eigen::Vector4d xyz_depth;
243-
xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
244-
((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
245-
depth,
246-
1;
247-
248-
// Transform to RGB camera frame
249-
Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
250-
251-
// Project to (u,v) in RGB image
252-
double inv_Z = 1.0 / xyz_rgb.z();
253-
int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
254-
if (u_rgb < 0 || u_rgb >= (int)registered_msg->width)
255-
continue;
256-
257-
int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
258-
if (v_rgb < 0 || v_rgb >= (int)registered_msg->height)
284+
int u_rgb;
285+
int v_rgb;
286+
T new_depth;
287+
if (!transform_depth(depth_to_rgb, u, v,
288+
depth_model_, rgb_model_,
289+
inv_depth_fx, inv_depth_fy,
290+
dst_width, dst_height,
291+
depth,
292+
u_rgb, v_rgb, new_depth)) {
259293
continue;
294+
}
260295

261296
T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
262-
T new_depth = DepthTraits<T>::fromMeters(xyz_rgb.z());
263297
// Validity and Z-buffer checks
264298
if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
265299
reg_depth = new_depth;
300+
266301
}
267302
else
268303
{
269-
// TODO(lucasw) replace same code with for loop
270-
// Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
271-
Eigen::Vector4d xyz_depth_1, xyz_depth_2;
272-
xyz_depth_1 << ((u-0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
273-
((v-0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
274-
depth,
275-
1;
276-
// Transform to RGB camera frame
277-
Eigen::Vector4d xyz_rgb_1 = depth_to_rgb * xyz_depth_1;
278-
// Project to (u,v) in RGB image
279-
const double inv_Z_1 = 1.0 / xyz_rgb_1.z();
280-
const int u_rgb_1 = (rgb_fx*xyz_rgb_1.x() + rgb_Tx)*inv_Z_1 + rgb_cx + 0.5;
281-
if (u_rgb_1 < 0 || u_rgb_1 >= (int)registered_msg->width)
282-
continue;
283-
const int v_rgb_1 = (rgb_fy*xyz_rgb_1.y() + rgb_Ty)*inv_Z_1 + rgb_cy + 0.5;
284-
if (v_rgb_1 < 0 || v_rgb_1 >= (int)registered_msg->height)
304+
// TODO(lucasw) loop on two -0.5, 0.5 vectors, keep track of u_min/max and v_min/max
305+
// as it goes
306+
int u_rgb_1;
307+
int v_rgb_1;
308+
T new_depth_1;
309+
if (!transform_depth(depth_to_rgb,
310+
u - 0.5, v - 0.5,
311+
depth_model_, rgb_model_,
312+
inv_depth_fx, inv_depth_fy,
313+
dst_width, dst_height,
314+
depth,
315+
u_rgb_1, v_rgb_1, new_depth_1)) {
316+
// TODO(lucasw) need to be able to handle partiall out of bounds squares here
285317
continue;
318+
}
286319

287-
// TODO(lucasw) this is identical to above except adding 0.5 instead of subtracting
288-
// TODO(lucasw) need a third and fourth position with u+0.5 and v-0.5 and u-0.5 and v+0.5
289-
// (and then could do the triangle rastering mentioned above, or just take the min
290-
// and max of all of them)
291-
xyz_depth_2 << ((u+0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
292-
((v+0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
293-
depth,
294-
1;
295-
// Transform to RGB camera frame
296-
Eigen::Vector4d xyz_rgb_2 = depth_to_rgb * xyz_depth_2;
297-
// Project to (u,v) in RGB image
298-
const double inv_Z_2 = 1.0 / xyz_rgb_2.z();
299-
const int u_rgb_2 = (rgb_fx*xyz_rgb_2.x() + rgb_Tx)*inv_Z_2 + rgb_cx + 0.5;
300-
if (u_rgb_2 < 0 || u_rgb_2 >= (int)registered_msg->width)
301-
continue;
302-
const int v_rgb_2 = (rgb_fy*xyz_rgb_2.y() + rgb_Ty)*inv_Z_2 + rgb_cy + 0.5;
303-
if (v_rgb_2 < 0 || v_rgb_2 >= (int)registered_msg->height)
320+
int u_rgb_2;
321+
int v_rgb_2;
322+
T new_depth_2;
323+
if (!transform_depth(depth_to_rgb,
324+
u + 0.5, v + 0.5,
325+
depth_model_, rgb_model_,
326+
inv_depth_fx, inv_depth_fy,
327+
dst_width, dst_height,
328+
depth,
329+
u_rgb_2, v_rgb_2, new_depth_2)) {
304330
continue;
331+
}
305332

306333
// fill in the square defined by uv range
307-
const T new_depth = DepthTraits<T>::fromMeters(0.5*(xyz_rgb_1.z()+xyz_rgb_2.z()));
334+
const T new_depth = DepthTraits<T>::fromMeters(0.5 * (new_depth_1 + new_depth_2));
308335
for (int nv=std::min(v_rgb_1, v_rgb_2); nv<=std::max(v_rgb_1, v_rgb_2); ++nv)
309336
{
310337
for (int nu=std::min(u_rgb_1, u_rgb_2); nu<=std::max(u_rgb_2, u_rgb_2); ++nu)

0 commit comments

Comments
 (0)