tentone / tello-ros2

ROS2 node for DJI Tello and Visual SLAM for mapping of indoor environments.
MIT License
149 stars 46 forks source link

ros2 topic echo /camera_info fails #6

Open zoldaten opened 1 year ago

zoldaten commented 1 year ago

hi! thanks a lot of tello-ros2!

im trying to get camera_info in second terminal with: ros2 topic echo /camera_info` but receive nothing. in main terminal i see:

Traceback (most recent call last):
[tello-1]   File "/usr/lib/python3.8/threading.py", line 932, in _bootstrap_inner
[tello-1]     self.run()
[tello-1]   File "/usr/lib/python3.8/threading.py", line 870, in run
[tello-1]     self._target(*self._args, **self._kwargs)
[tello-1]   File "/home/ubuntu/ros2_ws/install/tello/lib/python3.8/site-packages/tello/node.py", line 238, in status_loop
[tello-1]     msg.height = self.camera_info.image_height
[tello-1] AttributeError: 'dict' object has no attribute 'image_height'

i made may own calibration and put it there:

# Declare parameters
        self.node.declare_parameter('connect_timeout', 10.0)
        self.node.declare_parameter('tello_ip', '192.168.10.1')
        self.node.declare_parameter('tf_base', 'map')
        self.node.declare_parameter('tf_drone', 'drone')
        self.node.declare_parameter('tf_pub', False)
        self.node.declare_parameter('camera_info_file', '/home/ubuntu/ros2_ws/src/tello/tello/ost.yaml')

may be API has changed ? and do you know how to decrease camera shape as 960x720 hangs on my raspberry pi ?

tentone commented 1 year ago

Hello

What software version are you running on your tello?

Have not tested the project with latest versions of the firmware.

zoldaten commented 1 year ago

yes. i use the latest soft.

TSoli commented 9 months ago

I got the same error.

SlavenLeskovar commented 8 months ago

I am having the same problem. I am using Aruco Ros2 package and it keeps saying there's no camera info recieved. Also when i echo camera_info topic it shows no data.

TSoli commented 7 months ago

Ok so I found the issue. You actually need to specify the camera parameters (that you can get by calibrating the camera for example by doing this) using a yaml file. For example, I got the following parameters.

image_height: 720
image_width: 960

distortion_model: "plumb_bob"
distortion_coefficients:
  [
    -0.0699817593277033,
    -0.030309812668930222,
    -0.007853051329708314,
    -0.0016747628740195724,
  ]
camera_matrix:
  [
    742.1992742855476,
    0.0,
    454.12133045383564,
    0.0,
    742.7592370453168,
    312.0483639069177,
    0.0,
    0.0,
    1.0,
  ]
projection_matrix:
  [
    742.1992742855476,
    0.0,
    454.12133045383564,
    0.0,
    0.0,
    742.7592370453168,
    312.0483639069177,
    0.0,
    0.0,
    0.0,
    1.0,
    0.0,
  ]

Now you need to specify this as the camera_info_file in the launch file here by adding

            parameters=[
                {"connect_timeout": 10.0},
                {"tello_ip": "192.168.10.1"},
                {"tf_base": "map"},
                {"tf_drone": "drone"},
                {"camera_info_file": "./cam_info.yml"}, # This line here change it to wherever you put that config file above
            ],

Finally, there is a bug here that needs to be fixed it should be changed to

                if self.pub_camera_info.get_subscription_count() > 0:
                    msg = CameraInfo()
                    msg.height = self.camera_info.get("image_height") # change to .get() since these are dict values
                    msg.width = self.camera_info.get("image_width")
                    msg.distortion_model = self.camera_info.get("distortion_model")
                    msg.d = self.camera_info.get("distortion_coefficients") # Note these have changed to lower case letters
                    msg.k = self.camera_info.get("camera_matrix")
                    # msg.r = self.camera_info.get("rectification_matrix")
                    # above line is irrelevant since the drone has a monocular camera
                    msg.p = self.camera_info.get("projection_matrix")
                    self.pub_camera_info.publish(msg)

I might see if I can make a pull request later but I don't know if this repo is still maintained. Really only this last section is a bug.