0
$\begingroup$

before I get started, I'd like to point out that I have done thorough research and studied all similar issues I could find. Unfortunately I didn't find a solution that worked for my problem.

I am working on a package that uses the Ros2 built in image_publisher_node from ros-perception. I use a python launch-file which subscribes to a rts-stream from an ip-camera:

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
    use_sim_time = LaunchConfiguration('use_sim_time', default='false')
    camera_info_url = LaunchConfiguration('camera_info_url', default ='')
    return LaunchDescription([
        
        DeclareLaunchArgument(
            'camera_info_url',
            default_value='file://' + os.path.join(get_package_share_directory('marvin_data_collector'),'config','front_camera_info.yaml'),
            description='URL of the camera calibration file.'
            ),

        DeclareLaunchArgument(
            'use_sim_time',
            default_value='false',
            description='Use simulation clock if true'
            ),

        Node(
            package='image_publisher', executable='image_publisher_node', output='screen',
            arguments=['rtsp://admin:[email protected]:554/h264'],
            parameters=[{'camera_info_url': camera_info_url,
                        'use_sim_time': use_sim_time,
                        'publish_rate': 1.0,
                        'qos_overrides./parameter_events.publisher.depth': 10,
                        'qos_overrides./parameter_events.publisher.reliability': 'best_effort'}],
            remappings=[('__ns', '/front')]
            )
    ])

This works well enough, I get the image topics and the camera_info topic. However, it appears that the camera_info_url I use gets ignored.

This is the front_camera_info.yaml I use:

image_width: 1920
image_height: 1080
camera_name: narrow_stereo
camera_matrix:
  rows: 3
  cols: 3
  data: [2154.84924,    0.     , 1067.48426,
            0.     , 2183.19372,  486.52951,
            0.     ,    0.     ,    1.     ]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [-0.419139, 0.235887, 0.008504, -0.008708, 0.000000]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1., 0., 0.,
        0., 1., 0.,
        0., 0., 1.]
projection_matrix:
  rows: 3
  cols: 4
  data: [1970.31262,    0.     , 1071.2062 ,    0.     ,
            0.     , 2125.4436 ,  487.01673,    0.     ,
            0.     ,    0.     ,    1.     ,    0.     ]

When I launch I confirm the correct url with

ros2 param dump /front/ImagePublisher

which yields:

ros__parameters:
? ''
: image_raw:
    format: jpeg
    jpeg_quality: 95
    png_level: 3
    tiff:
      res_unit: inch
      xdpi: -1
      ydpi: -1
camera_info_url: file:///Git/isaac/install/marvin_data_collector/share/marvin_data_collector/config/front_camera_info.yaml
filename: rtsp://admin:[email protected]:554/h264
flip_horizontal: false
flip_vertical: false
frame_id: camera
publish_rate: 1.0
qos_overrides:
  /parameter_events:
    publisher:
      depth: 10
      durability: volatile
      history: keep_last
      reliability: best_effort
retry: false
timeout: 2000
use_sim_time: false

But when I confirm by looking at the camera_info being published with

ros2 topic echo /front/camera_info

I get:

header:
  stamp:
    sec: 1717668777
    nanosec: 101004015
  frame_id: camera
height: 1080
width: 1920
distortion_model: plumb_bob
d:
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
k:
- 1.0
- 0.0
- 960.0
- 0.0
- 1.0
- 540.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
- 960.0
- 0.0
- 0.0
- 1.0
- 540.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

Obviously the config gets ignored, I just don't understand why. In a different post it was mentioned that perhaps the config values may be out of bounds. So I also tried with a config file that had minimal changes compared to the camera_info that gets published. But even that didn't work.

$\endgroup$
0

1 Answer 1

1
$\begingroup$

It seems this is a bug in the image-publisher Node. The parameter camera_info_url is not loaded correctly.

Solution was to set the parameter after the node was launched.

This can be done at the end of the launchfile doing something like this:

ExecuteProcess(
        cmd=['ros2', 'param', 'set', '/front/ImagePublisher', 'camera_info_url', front_camera_info_url],
        output='screen'
        ),
$\endgroup$
0

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.