mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
879 stars 989 forks source link

Multiple nodes with the same name created if mavros::uas::UAS is loaded into a component container #1919

Open ugol-1 opened 11 months ago

ugol-1 commented 11 months ago

Issue details

When the mavros::uas::UAS component is loaded into a component container, it creates multiple nodes with the same name as the component manager name. It seems that each plugin node gets the name of the component manager.

Launch file:

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode

def generate_launch_description():
    fcu_url_launch_arg = DeclareLaunchArgument(
        "fcu_url",
        default_value = "/dev/ttyACM0:115200"
    )

    mavros_uas_node = ComposableNodeContainer(
        name = 'MavrosComponentManager',
        namespace = 'mavros',
        package = 'rclcpp_components',
        executable = 'component_container_mt',
        composable_node_descriptions = [
            ComposableNode(
                name = "uas",
                namespace = 'mavros',
                package = 'mavros',
                plugin = 'mavros::uas::UAS',
                parameters = [{
                    "fcu_url": LaunchConfiguration("fcu_url"),
                    "gcs_url": "",
                    "tgt_system": 1,
                    "tgt_component": 1,
                    "fcu_protocol": "v2.0",
                    "plugin_allowlist": [
                        "sys_status",
                    ]
                }],
                extra_arguments = [{
                    "use_intra_process_comms": True
                }]
            )
        ],
    )

    return LaunchDescription([
        fcu_url_launch_arg,
        mavros_uas_node,
    ])

MAVROS version and platform

Mavros: 2.6.0-1jammy.20230912.120519 ROS: Iron Ubuntu: 22.04

Autopilot type and version

[x] ArduPilot [ ] PX4

Version: 4.3.7

Node logs

[INFO] [launch]: All log files can be found below /home/pi/.ros/log/2023-11-02-19-48-02-226047-malina-2-14196
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container_mt-1]: process started with pid [14211]
[component_container_mt-1] [INFO] [1698947283.164913486] [mavros.MavrosComponentManager]: Load Library: /opt/ros/iron/lib/libmavros.so
[component_container_mt-1] [INFO] [1698947283.191213946] [mavros.MavrosComponentManager]: Found class: rclcpp_components::NodeFactoryTemplate<mavros::router::Router>
[component_container_mt-1] [INFO] [1698947283.191353499] [mavros.MavrosComponentManager]: Found class: rclcpp_components::NodeFactoryTemplate<mavros::uas::UAS>
[component_container_mt-1] [INFO] [1698947283.191392017] [mavros.MavrosComponentManager]: Instantiate class: rclcpp_components::NodeFactoryTemplate<mavros::uas::UAS>
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/mavros/uas' in container '/mavros/MavrosComponentManager'
[component_container_mt-1] [INFO] [1698947283.349010485] [mavros.uas]: UAS Executor started, threads: 4
[component_container_mt-1] [INFO] [1698947283.349032817] [mavros.uas]: Plugin actuator_control ignored
[component_container_mt-1] [INFO] [1698947283.349877488] [mavros.uas]: Plugin altitude ignored
[component_container_mt-1] [INFO] [1698947283.349957801] [mavros.uas]: Plugin command ignored
[component_container_mt-1] [INFO] [1698947283.350022707] [mavros.uas]: Plugin ftp ignored
[component_container_mt-1] [INFO] [1698947283.350084484] [mavros.uas]: Plugin geofence ignored
[component_container_mt-1] [INFO] [1698947283.350144242] [mavros.uas]: Plugin global_position ignored
[component_container_mt-1] [INFO] [1698947283.350199130] [mavros.uas]: Plugin home_position ignored
[component_container_mt-1] [INFO] [1698947283.350256500] [mavros.uas]: Plugin imu ignored
[component_container_mt-1] [INFO] [1698947283.350309147] [mavros.uas]: Plugin local_position ignored
[component_container_mt-1] [INFO] [1698947283.350362720] [mavros.uas]: Plugin manual_control ignored
[component_container_mt-1] [INFO] [1698947283.350414571] [mavros.uas]: Plugin nav_controller_output ignored
[component_container_mt-1] [INFO] [1698947283.350469348] [mavros.uas]: Plugin param ignored
[component_container_mt-1] [INFO] [1698947283.350523865] [mavros.uas]: Plugin rallypoint ignored
[component_container_mt-1] [INFO] [1698947283.350580586] [mavros.uas]: Plugin rc_io ignored
[component_container_mt-1] [INFO] [1698947283.350636863] [mavros.uas]: Plugin setpoint_accel ignored
[component_container_mt-1] [INFO] [1698947283.350691196] [mavros.uas]: Plugin setpoint_attitude ignored
[component_container_mt-1] [INFO] [1698947283.350746472] [mavros.uas]: Plugin setpoint_position ignored
[component_container_mt-1] [INFO] [1698947283.350800508] [mavros.uas]: Plugin setpoint_raw ignored
[component_container_mt-1] [INFO] [1698947283.350855119] [mavros.uas]: Plugin setpoint_trajectory ignored
[component_container_mt-1] [INFO] [1698947283.350911247] [mavros.uas]: Plugin setpoint_velocity ignored
[component_container_mt-1] [WARN] [1698947283.391710062] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[component_container_mt-1] [INFO] [1698947283.449474224] [mavros.uas]: Plugin sys_status created
[component_container_mt-1] [INFO] [1698947283.449711794] [mavros.uas]: Plugin sys_status initialized
[component_container_mt-1] [INFO] [1698947283.449773533] [mavros.uas]: Plugin sys_time ignored
[component_container_mt-1] [INFO] [1698947283.449820310] [mavros.uas]: Plugin waypoint ignored
[component_container_mt-1] [INFO] [1698947283.449861236] [mavros.uas]: Plugin wind_estimation ignored
[component_container_mt-1] [INFO] [1698947283.455670059] [mavros.uas]: Built-in SIMD instructions: ARM NEON
[component_container_mt-1] [INFO] [1698947283.455786945] [mavros.uas]: Built-in MAVLink package version: 2023.9.9
[component_container_mt-1] [INFO] [1698947283.455830130] [mavros.uas]: Known MAVLink dialects: common ardupilotmega ASLUAV AVSSUAS all csAirLink cubepilot development icarous matrixpilot paparazzi standard storm32 uAvionix ualberta
[component_container_mt-1] [INFO] [1698947283.455866370] [mavros.uas]: MAVROS UAS via /uas1 started. MY ID 1.191, TARGET ID 1.1

Diagnostics

header:
  stamp:
    sec: 1698947386
    nanosec: 433098033
  frame_id: ''
status:
- level: "\x02"
  name: 'uas: MAVROS UAS'
  message: disconnected
  hardware_id: uas:///uas1
  values: []
- level: "\0"
  name: 'uas: System'
  message: Normal
  hardware_id: uas:///uas1
  values:
  - key: Sensor present
    value: '0x00000000'
  - key: Sensor enabled
    value: '0x00000000'
  - key: Sensor health
    value: '0x00000000'
  - key: CPU Load (%)
    value: '0.0'
  - key: Drop rate (%)
    value: '0.0'
  - key: Errors comm
    value: '0'
  - key: 'Errors count #1'
    value: '0'
  - key: 'Errors count #2'
    value: '0'
  - key: 'Errors count #3'
    value: '0'
  - key: 'Errors count #4'
    value: '0'
- level: "\x02"
  name: 'uas: Battery'
  message: No data
  hardware_id: uas:///uas1
  values:
  - key: Voltage
    value: '-1.00'
  - key: Current
    value: '0.0'
  - key: Remaining
    value: '0.0'
- level: "\x02"
  name: 'uas: Heartbeat'
  message: No events recorded.
  hardware_id: uas:///uas1
  values:
  - key: Heartbeats since startup
    value: '0'
  - key: Frequency (Hz)
    value: '0.000000'
  - key: Vehicle type
    value: Generic micro air vehicle
  - key: Autopilot type
    value: Generic autopilot
  - key: Mode
    value: ''
  - key: System status
    value: UNINIT
---

Node list

$ ros2 node list
WARNING: Be aware that there are nodes in the graph that share an exact name, which can have unintended side effects.
/launch_ros_14237
/mavros/MavrosComponentManager
/mavros/MavrosComponentManager
/mavros/transform_listener_impl_aaab08278b40
/mavros/uas
vooon commented 11 months ago

But where is the multiple nodes? BTW UAS know nothing about fcu_url nor gcs_url.

ugol-1 commented 11 months ago

But where is the multiple nodes? BTW UAS know nothing about fcu_url nor gcs_url.

[component_container_mt-1] [WARN] [1698947283.391710062] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.

This is printed for each plugin node when it is loaded. Also check the output of ros2 node list. Every plugin node gets the same name as the component manager.