pal-robotics/aruco_ros

ROS Indigo weird TF errors

Closed this issue · 12 comments

Hello I am trying to use this with a simple image_raw and camera_info topic but I am always getting the following errors:

TF_NAN_INPUT: Ignoring transform for child_frame_id "marker_frame" from authority "unknown_publisher" because of a nan value in the transform (-nan -inf -nan) (-0.542478 -0.431334 0.485505 0.532872) at line 244 in /tmp/binarydeb/ros-indigo-tf2-0.5.17/src/buffer_core.cpp

So it seems there is some rotation calculation but no translation.

I am using:

<arg name="marker_frame"    default="marker_frame"/>
<arg name="ref_frame"       default=""/>  <!-- leave empty and the pose will be published wrt param parent_name -->
<param name="camera_frame"       value="base_link"/>

This is just the simple example. I used it with our robots tf-publisher as well, where the camera_frame was linked to the rest of the robot, but still the same issue.

Looking at the image /aruco_single/result I can see a valid detection.

Any idea what is happening?

Hmm, which field do you have in mind? Maybe the frame in the header of the camera info?
Here is the camera info:

header: 
  seq: 1699
  stamp: 
    secs: 1528207593
    nsecs: 3959129088
  frame_id: camera_mlx_frame_link
height: 512
width: 1024
distortion_model: plumb_bob
D: [-0.37344000000000005, 0.13855, -0.023670000000000004, -0.00028000000000000003, 0.00062]
K: [551.29784, 0.0, 0.0, -0.27212000000000003, 551.16795, 0.0, 501.52976, 248.17503, 1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [551.29784, 0.0, 0.0, -0.27212000000000003, 551.16795, 0.0, 501.52976, 248.17503, 1.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
---

Yeap! Here you are.
Thanks for looking into this!

You can try to set some made up frame.
Was trying the same, but without luck 😇

What's the ID and size of the marker?

And probably post your launch file.

Reverse engineered is marker 1... I don't know the size tho.

Your camera info is wrong. A default camera info like:

rostopic pub /twizy/camera/mlx/camera_info sensor_msgs/CameraInfo "header: 
  seq: 0
  stamp: 
    secs: 0
    nsecs: 0
  frame_id: "camera_mlx_frame_link"
height: 512
width: 1024
distortion_model: "plumb_bob"
D: [0.0, 0.0, 0.0, 0.0, 0.0]
K: [1.0, 0.0, 512.0, 0.0, 1.0, 256.0, 0.0, 0.0, 1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [1.0, 0.0, 512.0, 0.0, 0.0, 1.0, 256.0, 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"

Provides detections, with a launchfile like:

<launch>

    <arg name="markerId"        default="1"/>
    <arg name="markerSize"      default="0.1"/>    <!-- in m -->
    <arg name="marker_frame"    default="aruco_marker_frame"/>
    <arg name="ref_frame"       default=""/>  <!-- leave empty and the pose will be published wrt param parent_name -->
    <arg name="corner_refinement" default="LINES" /> <!-- NONE, HARRIS, LINES, SUBPIX -->


    <node pkg="aruco_ros" type="single" name="aruco_single">
        <remap from="/camera_info" to="/twizy/camera/mlx/camera_info" />
        <remap from="/image" to="/twizy/camera/mlx/undistorted_image_raw" />
        <param name="image_is_rectified" value="True"/>
        <param name="marker_size"        value="$(arg markerSize)"/>
        <param name="marker_id"          value="$(arg markerId)"/>
        <param name="reference_frame"    value="$(arg ref_frame)"/>   <!-- frame in which the marker pose will be refered -->
        <param name="camera_frame"       value="camera_mlx_frame_link"/>
        <param name="marker_frame"       value="$(arg marker_frame)" />
        <param name="corner_refinement"  value="$(arg corner_refinement)" />
    </node>

</launch>

screenshot from 2018-06-06 02-10-45

Marker size is 0.17m and marker id=1 (indeed). So you are saying probably the camera matrix K is wrong?
The launch file also correct 😉.

I am gonna check all the camera matrices to make sure they are correct. Thanks! (I'll let you know)

Both K & P look wrong if you compare the default camera info (perfect camera values) to yours. Seems values are shifted positions. Good luck. Also, next time, please post all necessary information to help you on the issue, makes things way easier.

Yes both are wrong, you are right. There is an error in the matlab script that generate those.

Also, next time, please post all necessary information to help you on the issue, makes things way easier.

Yeah my bad, sorry.
Thanks for looking into this!

https://memegenerator.net/img/instances/81927730/old-man-yells-at-matlab.jpg

haha good luck.