Skip to content

Issues with ROS Args in image_transport_py #357

Open
@atyshka

Description

@atyshka

I'm glad to see the python API launching in Kilted (#248, #323)! Unfortunately I'm running into issues using it, as it seems that namespacing is broken for python. If I place my python node in the namespace camera, the python node name gets prefixed but the secondary node created by ImageTransport does not receive the namespace and neither do the topics it interfaces with.

Minimal reproducible example: ros2 run image_transport_tutorials_py my_subscriber --ros-args -r __ns:=/demo

I dug into the code, and it seems the issue is here in pybind_image_transport.cpp:

  pybind11::class_<image_transport::ImageTransport>(m, "ImageTransport")
  .def(
    pybind11::init(
      [](const std::string & node_name, const std::string & image_transport,
      const std::string & launch_params_filepath) {
        if (!rclcpp::ok()) {
          rclcpp::init(0, nullptr);
        }
        rclcpp::NodeOptions node_options;

        if (!launch_params_filepath.empty()) {
          node_options.allow_undeclared_parameters(true)
          .automatically_declare_parameters_from_overrides(true)
          .arguments({"--ros-args", "--params-file", launch_params_filepath});
        } else if (!image_transport.empty()) {
          node_options.allow_undeclared_parameters(true)
          .automatically_declare_parameters_from_overrides(true)
          .append_parameter_override("image_transport", image_transport);
        }

        rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options);

rclcpp is initializing on its own, without any --ros-args.

Do you have any suggestions for the best way to resolve this? I'm not sure if there are any other ros2 packages that face similar challenges with python bindings. I can submit a PR if we agree on an approach.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions