ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

depthimage_to_laserscan: Cannot call rectifyPoint when distortion is unknown

asked 2020-03-17 18:13:37 -0500

Eugene gravatar image

I'm trying to run the depthimage_to_laserscan with an MYNT EYE camera. I get this output (see the error in the end):

SUMMARY
========

PARAMETERS
 * /depthimage_to_laserscan/output_frame_id: base_link
 * /depthimage_to_laserscan/scan_height: 3
 * /rosdistro: melodic
 * /rosversion: 1.14.3

NODES
  /
depthimage_to_laserscan (depthimage_to_laserscan/depthimage_to_laserscan)
gmapping_node (gmapping/slam_gmapping)

ROS_MASTER_URI=http://localhost:11311

process[depthimage_to_laserscan-1]: started with pid [17275]
process[gmapping_node-2]: started with pid [17276]
[ERROR] [1584483469.757240526]: Could not convert depth image to laserscan: Cannot call rectifyPoint when distortion is unknown.

My platform: Ubuntu 18.04 (x64). I use ROS Melodic. The "depthimage_to_laserscan" package version is 1.0.8.

The depthimage_to_laserscan node is subscribed to 2 topics (I checked it with rqt_graph):

  1. /mynteye/depth/image_raw
  2. /mynteye/depth/camera_info

I used "rostopic echo" command to check the messages published to the "/mynteye/depth/camera_info" topic. This message is published continuously:

---
header: 
  seq: 22519
  stamp: 
    secs: 1584483432
    nsecs: 228966713
  frame_id: "mynteye_depth_frame"
height: 480
width: 752
distortion_model: "KANNALA_BRANDT"
D: [-0.031170006043024615, 0.02301973375803421, -0.0352997004132725, 0.016822330752111488, 0.0]
K: [366.9709661238975, 0.0, 370.60059198845664, 0.0, 366.9835673211366, 235.15553431559664, 0.0, 0.0, 1.0]
R: [0.9999976403807529, 0.0012593887617488196, -0.0017700770811053344, -0.0012566534577968802, 0.9999980160222749, 0.0015455657866886375, 0.0017720200374941424, -0.0015433377662572895, 0.9999972390229515]
P: [367.166403809061, 0.0, 338.11387634277344, 0.0, 0.0, 367.166403809061, 188.29586029052734, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 0
binning_y: 0
roi: 
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False
---

It looks like the distortion matrix is not empty. What can go wrong there? Maybe the problem is in the unsupported distortion model "KANNALA_BRANDT"?

Thanks, Eugene

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-03-18 03:20:22 -0500

gvdhoorn gravatar image

updated 2020-03-18 03:22:48 -0500

Maybe the problem is in the unsupported distortion model "KANNALA_BRANDT"?

That is a likely cause, yes.

As sensor_msgs/CameraInfo mentions, legal values for that field are defined in sensor_msgs/distortion_models.h. Looking at that file shows (from here):

const std::string PLUMB_BOB = "plumb_bob";
const std::string RATIONAL_POLYNOMIAL = "rational_polynomial";
const std::string EQUIDISTANT = "equidistant";

KANNALA_BRANDT is not in that list.

It looks like it's also called a fisheye distortion model, and for that model there are several PRs open. The one against ros/common_msgs would be ros/common_msgs#151.

You may be able to get an idea of the current state of support for this particular distortion model from the linked issues and PRs.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2020-03-17 17:52:21 -0500

Seen: 774 times

Last updated: Mar 18 '20