UniversalRobots / Universal_Robots_ROS2_Driver

Universal Robots ROS2 driver supporting CB3 and e-Series
BSD 3-Clause "New" or "Revised" License
424 stars 220 forks source link

GPIO controller prints Configure UR gpio controller with tf_prefix all frequently #676

Open fmauch opened 1 year ago

fmauch commented 1 year ago

Since #594 the GPIO controller prints

Configure UR gpio controller with tf_prefix: <tf_prefix>

quite regularly (~every 2 secs). I'm not sure whether this should be normal from the documentations, but I suggest to remove the output / making this a print once.

@firesurfer did you experience this in your applications, as well?

firesurfer commented 1 year ago

@fmauch I didn't experience this in my application. We also didn't see this while testing last week didn't we?

Seeing this line regularly means that somehow the command_interface_configuration is called every 2 seconds (https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/fb5972dcd28425a73da3aa524493c9bc886f0f2c/ur_controllers/src/gpio_controller.cpp#LL66C1-L66C1) which is definitely shouldn't.

I agree with removing this output, but nevertheless you should check your system setup why it regularly reinits (is it really a reinit) the controller ( or creates a new controller instance).

firesurfer commented 1 year ago

@fmauch Did you manage to further investigate this issue?

firesurfer commented 1 year ago

I managed to repoduce this issue (even though I do not get a regular printout). I think it is ros2 control related. For some reason it calls for many operations command_interface_configuration. I guess what happens there is that the controller manager creates for certain operations a new instance and configures it.

fmauch commented 1 year ago

Yes, I've also experienced it only in certain circumstances. For example, when having the rqt_joint_trajectory_controller open, this seems to get called regularly. But apart from that I didn't further investigate this.

firesurfer commented 1 year ago

I guess this is an issue which should be reported in ros2_control then.

niemsoen commented 1 year ago

We have the same problem with our workspace that includes the UR5. Ever since the binary release 2.2.6-1 in May 2023 our driver broke due to the tf_prefix problem in #677 . With the release of the driver binary 2.2.8-1, we can start the driver again (sort of) with our tf_prefix "ur5/", however the scaled_joint_trajectory_controller doesn't get activated (checked with ros2 control list_controllers).

The same print out as described by @fmauch above (Configure UR gpio controller with tf_prefix: ur5/) appears repeatedly with very high frequency (multiple per second) until the driver eventually dies.

Log Output

see log ``` [INFO] [launch]: All log files can be found below /home/ipk/.ros/log/2023-07-11-13-26-55-572190-tendobot-NUC11TNHv7-22359 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [dashboard_client-2]: process started with pid [22363] [INFO] [controller_stopper_node-3]: process started with pid [22365] [INFO] [ur_ros2_control_node-1]: process started with pid [22361] [INFO] [spawner-4]: process started with pid [22367] [INFO] [spawner-5]: process started with pid [22369] [INFO] [spawner-6]: process started with pid [22371] [INFO] [spawner-7]: process started with pid [22373] [INFO] [spawner-8]: process started with pid [22375] [INFO] [spawner-9]: process started with pid [22377] [controller_stopper_node-3] [INFO] [1689074815.983810577] [Controller stopper]: Waiting for switch controller service to come up on controller_manager/switch_controller [dashboard_client-2] [INFO] [1689074815.991457950] [UR_Client_Library]: Connected: Universal Robots Dashboard Server [dashboard_client-2] [ur_ros2_control_node-1] [INFO] [1689074815.991445281] [resource_manager]: Loading hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994054377] [resource_manager]: Initialize hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994132404] [resource_manager]: Successful initialization of hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994291225] [resource_manager]: 'configure' hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994299654] [resource_manager]: Successful 'configure' of hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994325629] [resource_manager]: 'activate' hardware 'ur5' [ur_ros2_control_node-1] [INFO] [1689074815.994334695] [URPositionHardwareInterface]: Starting ...please wait... [ur_ros2_control_node-1] [INFO] [1689074815.994348607] [URPositionHardwareInterface]: Initializing driver... [ur_ros2_control_node-1] [INFO] [1689074815.996145861] [UR_Client_Library]: Producer thread: SCHED_FIFO OK [ur_ros2_control_node-1] [INFO] [1689074815.996179174] [UR_Client_Library]: Thread priority is 99 [ur_ros2_control_node-1] [INFO] [1689074816.345678878] [UR_Client_Library]: Negotiated RTDE protocol version to 2. [ur_ros2_control_node-1] [INFO] [1689074816.345880266] [UR_Client_Library]: Setting up RTDE communication with frequency 125.000000 [ur_ros2_control_node-1] [INFO] [1689074817.381077024] [URPositionHardwareInterface]: Calibration checksum: 'calib_9015960103717665060'. [ur_ros2_control_node-1] [INFO] [1689074817.381831862] [UR_Client_Library]: Producer thread: SCHED_FIFO OK [ur_ros2_control_node-1] [INFO] [1689074817.381863241] [UR_Client_Library]: Thread priority is 99 [spawner-5] [INFO] [1689074818.297510063] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available [spawner-7] [INFO] [1689074818.300634633] [spawner_speed_scaling_state_broadcaster]: Waiting for '/controller_manager' services to be available [spawner-9] [INFO] [1689074818.303022258] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available [spawner-6] [INFO] [1689074818.303517541] [spawner_io_and_status_controller]: Waiting for '/controller_manager' services to be available [spawner-4] [INFO] [1689074818.308136974] [spawner_scaled_joint_trajectory_controller]: Waiting for '/controller_manager' services to be available [spawner-8] [INFO] [1689074818.308232326] [spawner_force_torque_sensor_broadcaster]: Waiting for '/controller_manager' services to be available [ur_ros2_control_node-1] [INFO] [1689074818.400586665] [URPositionHardwareInterface]: Calibration checked successfully. [ur_ros2_control_node-1] [INFO] [1689074818.400697561] [URPositionHardwareInterface]: System successfully started! [ur_ros2_control_node-1] [INFO] [1689074818.400715563] [resource_manager]: Successful 'activate' of hardware 'ur5' [controller_stopper_node-3] [INFO] [1689074818.405609503] [Controller stopper]: Service available [controller_stopper_node-3] [INFO] [1689074818.405633038] [Controller stopper]: Waiting for list controllers service to come up on controller_manager/list_controllers [controller_stopper_node-3] [INFO] [1689074818.405641859] [Controller stopper]: Service available [ur_ros2_control_node-1] [INFO] [1689074818.406616826] [UR_Client_Library]: Producer thread: SCHED_FIFO OK [ur_ros2_control_node-1] [INFO] [1689074818.406631961] [UR_Client_Library]: Thread priority is 99 [ur_ros2_control_node-1] [INFO] [1689074818.513753347] [controller_manager]: Loading controller 'io_and_status_controller' [ur_ros2_control_node-1] [INFO] [1689074818.519978732] [controller_manager]: Loading controller 'forward_position_controller' [spawner-6] [INFO] [1689074818.520375234] [spawner_io_and_status_controller]: Loaded io_and_status_controller [ur_ros2_control_node-1] [INFO] [1689074818.527812929] [controller_manager]: Loading controller 'scaled_joint_trajectory_controller' [spawner-9] [INFO] [1689074818.528350734] [spawner_forward_position_controller]: Loaded forward_position_controller [ur_ros2_control_node-1] [INFO] [1689074818.535655648] [controller_manager]: Loading controller 'force_torque_sensor_broadcaster' [spawner-4] [INFO] [1689074818.536128082] [spawner_scaled_joint_trajectory_controller]: Loaded scaled_joint_trajectory_controller [ur_ros2_control_node-1] [INFO] [1689074818.543668460] [controller_manager]: Configuring controller 'io_and_status_controller' [ur_ros2_control_node-1] [INFO] [1689074818.543824007] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.543914827] [controller_manager]: Configuring controller 'forward_position_controller' [spawner-8] [INFO] [1689074818.544259151] [spawner_force_torque_sensor_broadcaster]: Loaded force_torque_sensor_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.545235115] [forward_position_controller]: configure successful [ur_ros2_control_node-1] [INFO] [1689074818.545361338] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.545552075] [controller_manager]: Configuring controller 'scaled_joint_trajectory_controller' [ur_ros2_control_node-1] [INFO] [1689074818.545649815] [scaled_joint_trajectory_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter. [ur_ros2_control_node-1] [INFO] [1689074818.545683129] [scaled_joint_trajectory_controller]: Command interfaces are [position] and state interfaces are [position velocity]. [ur_ros2_control_node-1] [INFO] [1689074818.545701049] [scaled_joint_trajectory_controller]: Using 'splines' interpolation method. [ur_ros2_control_node-1] [INFO] [1689074818.546563729] [scaled_joint_trajectory_controller]: Controller state will be published at 100.00 Hz. [ur_ros2_control_node-1] [INFO] [1689074818.548070335] [scaled_joint_trajectory_controller]: Action status changes will be monitored at 20.00 Hz. [ur_ros2_control_node-1] [INFO] [1689074818.550336803] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.550517882] [controller_manager]: Configuring controller 'force_torque_sensor_broadcaster' [ur_ros2_control_node-1] [INFO] [1689074818.551114015] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.551162576] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.551321258] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.555584149] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.559659004] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-6] [INFO] [1689074818.560276372] [spawner_io_and_status_controller]: Configured and activated io_and_status_controller [ur_ros2_control_node-1] [ERROR] [1689074818.567561700] [controller_manager]: Can't activate controller 'scaled_joint_trajectory_controller': State interface with key 'speed_scaling/speed_scaling_factor' does not exist [ur_ros2_control_node-1] [INFO] [1689074818.567804134] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.575812637] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-4] [INFO] [1689074818.576842739] [spawner_scaled_joint_trajectory_controller]: Configured and activated scaled_joint_trajectory_controller [ur_ros2_control_node-1] [ERROR] [1689074818.583526559] [controller_manager]: Can't activate controller 'force_torque_sensor_broadcaster': State interface with key 'tcp_fts_sensor/force.x' does not exist [ur_ros2_control_node-1] [INFO] [1689074818.583674511] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.591645707] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.591963710] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-8] [INFO] [1689074818.592194579] [spawner_force_torque_sensor_broadcaster]: Configured and activated force_torque_sensor_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.592302719] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.593012217] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.593356898] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.594126699] [controller_manager]: Loading controller 'joint_state_broadcaster' [ur_ros2_control_node-1] [INFO] [1689074818.599757860] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.600115237] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-5] [INFO] [1689074818.600313545] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.600474929] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.600781522] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.601114555] [controller_manager]: Loading controller 'speed_scaling_state_broadcaster' [ur_ros2_control_node-1] [INFO] [1689074818.606348432] [speed_scaling_state_broadcaster]: Loading UR SpeedScalingStateBroadcaster with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.607593913] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.607803420] [controller_manager]: Configuring controller 'joint_state_broadcaster' [ur_ros2_control_node-1] [INFO] [1689074818.607858030] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published [spawner-7] [INFO] [1689074818.608110880] [spawner_speed_scaling_state_broadcaster]: Loaded speed_scaling_state_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.609222151] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.609466649] [controller_manager]: Configuring controller 'speed_scaling_state_broadcaster' [ur_ros2_control_node-1] [INFO] [1689074818.609506454] [speed_scaling_state_broadcaster]: Publisher rate set to : 100.0 Hz [ur_ros2_control_node-1] [INFO] [1689074818.609998717] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.615761454] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.623897797] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-5] [INFO] [1689074818.624310992] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.631608907] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.639676493] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.640065863] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [spawner-7] [INFO] [1689074818.640262088] [spawner_speed_scaling_state_broadcaster]: Configured and activated speed_scaling_state_broadcaster [ur_ros2_control_node-1] [INFO] [1689074818.640416592] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.640726362] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ [ur_ros2_control_node-1] [INFO] [1689074818.641018923] [io_and_status_controller]: Configure UR gpio controller with tf_prefix: ur5/ ........... this keeps coming until the driver eventually dies ```

Launch File

slightly adapted from original source only in terms of config file paths, using calibrated kinematics instead of default, not using robot state publisher because we already have one of our own and custom robot_description.

see launch file ```python # Copyright (c) 2021 PickNik, Inc. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the {copyright_holder} nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Denis Stogl from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, OpaqueFunction from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution def launch_setup(context, *args, **kwargs): # Initialize Arguments ur_type = LaunchConfiguration("ur_type") robot_ip = LaunchConfiguration("robot_ip") safety_limits = LaunchConfiguration("safety_limits") safety_pos_margin = LaunchConfiguration("safety_pos_margin") safety_k_position = LaunchConfiguration("safety_k_position") # General arguments runtime_config_package = LaunchConfiguration("runtime_config_package") controllers_file = LaunchConfiguration("controllers_file") description_package = LaunchConfiguration("description_package") description_file = LaunchConfiguration("description_file") tf_prefix = LaunchConfiguration("tf_prefix") use_fake_hardware = LaunchConfiguration("use_fake_hardware") fake_sensor_commands = LaunchConfiguration("fake_sensor_commands") controller_spawner_timeout = LaunchConfiguration("controller_spawner_timeout") initial_joint_controller = LaunchConfiguration("initial_joint_controller") activate_joint_controller = LaunchConfiguration("activate_joint_controller") launch_rviz = LaunchConfiguration("launch_rviz") headless_mode = LaunchConfiguration("headless_mode") launch_dashboard_client = LaunchConfiguration("launch_dashboard_client") use_tool_communication = LaunchConfiguration("use_tool_communication") tool_parity = LaunchConfiguration("tool_parity") tool_baud_rate = LaunchConfiguration("tool_baud_rate") tool_stop_bits = LaunchConfiguration("tool_stop_bits") tool_rx_idle_chars = LaunchConfiguration("tool_rx_idle_chars") tool_tx_idle_chars = LaunchConfiguration("tool_tx_idle_chars") tool_device_name = LaunchConfiguration("tool_device_name") tool_tcp_port = LaunchConfiguration("tool_tcp_port") tool_voltage = LaunchConfiguration("tool_voltage") reverse_ip = LaunchConfiguration("reverse_ip") script_command_port = LaunchConfiguration("script_command_port") joint_limit_params = PathJoinSubstitution( [FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"] ) kinematics_params = PathJoinSubstitution( [FindPackageShare(description_package), "config", ur_type, "calibrated_kinematics.yaml"] ) physical_params = PathJoinSubstitution( [FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"] ) visual_params = PathJoinSubstitution( [FindPackageShare(description_package), "config", ur_type, "visual_parameters.yaml"] ) script_filename = PathJoinSubstitution( [FindPackageShare("ur_client_library"), "resources", "external_control.urscript"] ) input_recipe_filename = PathJoinSubstitution( [FindPackageShare("ur_robot_driver"), "resources", "rtde_input_recipe.txt"] ) output_recipe_filename = PathJoinSubstitution( [FindPackageShare("ur_robot_driver"), "resources", "rtde_output_recipe.txt"] ) robot_description_content = Command( [ PathJoinSubstitution([FindExecutable(name="xacro")]), " ", PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]), " ", "robot_ip:=", robot_ip, " ", "joint_limit_params:=", joint_limit_params, " ", "kinematics_params:=", kinematics_params, " ", "physical_params:=", physical_params, " ", "visual_params:=", visual_params, " ", "safety_limits:=", safety_limits, " ", "safety_pos_margin:=", safety_pos_margin, " ", "safety_k_position:=", safety_k_position, " ", "name:=", ur_type, " ", "script_filename:=", script_filename, " ", "input_recipe_filename:=", input_recipe_filename, " ", "output_recipe_filename:=", output_recipe_filename, " ", "tf_prefix:=", tf_prefix, " ", "use_fake_hardware:=", use_fake_hardware, " ", "fake_sensor_commands:=", fake_sensor_commands, " ", "headless_mode:=", headless_mode, " ", "use_tool_communication:=", use_tool_communication, " ", "tool_parity:=", tool_parity, " ", "tool_baud_rate:=", tool_baud_rate, " ", "tool_stop_bits:=", tool_stop_bits, " ", "tool_rx_idle_chars:=", tool_rx_idle_chars, " ", "tool_tx_idle_chars:=", tool_tx_idle_chars, " ", "tool_device_name:=", tool_device_name, " ", "tool_tcp_port:=", tool_tcp_port, " ", "tool_voltage:=", tool_voltage, " ", "reverse_ip:=", reverse_ip, " ", "script_command_port:=", script_command_port, " ", ] ) robot_description = {"robot_description": robot_description_content} initial_joint_controllers = PathJoinSubstitution( [FindPackageShare(runtime_config_package), "config/ur5", controllers_file] ) rviz_config_file = PathJoinSubstitution( [FindPackageShare(description_package), "rviz", "tendobot.rviz"] ) # define update rate update_rate_config_file = PathJoinSubstitution( [ FindPackageShare(runtime_config_package), "config/ur5", ur_type.perform(context) + "_update_rate.yaml", ] ) control_node = Node( package="controller_manager", executable="ros2_control_node", parameters=[robot_description, update_rate_config_file, initial_joint_controllers], output="screen", condition=IfCondition(use_fake_hardware), ) ur_control_node = Node( package="ur_robot_driver", executable="ur_ros2_control_node", parameters=[robot_description, update_rate_config_file, initial_joint_controllers], output="screen", condition=UnlessCondition(use_fake_hardware), ) dashboard_client_node = Node( package="ur_robot_driver", condition=IfCondition(launch_dashboard_client) and UnlessCondition(use_fake_hardware), executable="dashboard_client", name="dashboard_client", output="screen", emulate_tty=True, parameters=[{"robot_ip": robot_ip}], ) tool_communication_node = Node( package="ur_robot_driver", condition=IfCondition(use_tool_communication), executable="tool_communication.py", name="ur_tool_comm", output="screen", parameters=[ { "robot_ip": robot_ip, "tcp_port": tool_tcp_port, "device_name": tool_device_name, } ], ) controller_stopper_node = Node( package="ur_robot_driver", executable="controller_stopper_node", name="controller_stopper", output="screen", emulate_tty=True, condition=UnlessCondition(use_fake_hardware), parameters=[ {"headless_mode": headless_mode}, {"joint_controller_active": activate_joint_controller}, { "consistent_controllers": [ "io_and_status_controller", "force_torque_sensor_broadcaster", "joint_state_broadcaster", "speed_scaling_state_broadcaster", ] }, ], ) rviz_node = Node( package="rviz2", condition=IfCondition(launch_rviz), executable="rviz2", name="rviz2", output="log", arguments=["-d", rviz_config_file], ) # Spawn controllers def controller_spawner(name, active=True): inactive_flags = ["--inactive"] if not active else [] return Node( package="controller_manager", executable="spawner", arguments=[ name, "--controller-manager", "/controller_manager", "--controller-manager-timeout", controller_spawner_timeout, ] + inactive_flags, ) controller_spawner_names = [ "joint_state_broadcaster", "io_and_status_controller", "speed_scaling_state_broadcaster", "force_torque_sensor_broadcaster", ] controller_spawner_inactive_names = ["forward_position_controller"] controller_spawners = [controller_spawner(name) for name in controller_spawner_names] + [ controller_spawner(name, active=False) for name in controller_spawner_inactive_names ] # There may be other controllers of the joints, but this is the initially-started one initial_joint_controller_spawner_started = Node( package="controller_manager", executable="spawner", arguments=[ initial_joint_controller, "-c", "/controller_manager", "--controller-manager-timeout", controller_spawner_timeout, ], condition=IfCondition(activate_joint_controller), ) initial_joint_controller_spawner_stopped = Node( package="controller_manager", executable="spawner", arguments=[ initial_joint_controller, "-c", "/controller_manager", "--controller-manager-timeout", controller_spawner_timeout, "--inactive", ], condition=UnlessCondition(activate_joint_controller), ) nodes_to_start = [ control_node, ur_control_node, dashboard_client_node, tool_communication_node, controller_stopper_node, rviz_node, initial_joint_controller_spawner_stopped, initial_joint_controller_spawner_started, ] + controller_spawners return nodes_to_start def generate_launch_description(): declared_arguments = [] # UR specific arguments declared_arguments.append( DeclareLaunchArgument( "ur_type", default_value="ur5", description="Type/series of used UR robot.", choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"], ) ) declared_arguments.append( DeclareLaunchArgument( "robot_ip", default_value="192.168.12.180", description="IP address by which the robot can be reached." ) ) declared_arguments.append( DeclareLaunchArgument( "safety_limits", default_value="true", description="Enables the safety limits controller if true.", ) ) declared_arguments.append( DeclareLaunchArgument( "safety_pos_margin", default_value="0.15", description="The margin to lower and upper limits in the safety controller.", ) ) declared_arguments.append( DeclareLaunchArgument( "safety_k_position", default_value="20", description="k-position factor in the safety controller.", ) ) # General arguments declared_arguments.append( DeclareLaunchArgument( "runtime_config_package", default_value="tendobot_description", description='Package with the controller\'s configuration in "config" folder. \ Usually the argument is not set, it enables use of a custom setup.', ) ) declared_arguments.append( DeclareLaunchArgument( "controllers_file", default_value="ur_controllers.yaml", description="YAML file with the controllers configuration.", ) ) declared_arguments.append( DeclareLaunchArgument( "description_package", default_value="tendobot_description", description="Description package with robot URDF/XACRO files. Usually the argument \ is not set, it enables use of a custom description.", ) ) declared_arguments.append( DeclareLaunchArgument( "description_file", default_value="tendobot.urdf.xacro", description="URDF/XACRO description file with the robot.", ) ) declared_arguments.append( DeclareLaunchArgument( "tf_prefix", default_value='"ur5/"', description="tf_prefix of the joint names, useful for \ multi-robot setup. If changed, also joint names in the controllers' configuration \ have to be updated.", ) ) declared_arguments.append( DeclareLaunchArgument( "use_fake_hardware", default_value="false", description="Start robot with fake hardware mirroring command to its states.", ) ) declared_arguments.append( DeclareLaunchArgument( "fake_sensor_commands", default_value="false", description="Enable fake command interfaces for sensors used for simple simulations. \ Used only if 'use_fake_hardware' parameter is true.", ) ) declared_arguments.append( DeclareLaunchArgument( "headless_mode", default_value="false", description="Enable headless mode for robot control", ) ) declared_arguments.append( DeclareLaunchArgument( "controller_spawner_timeout", default_value="10", description="Timeout used when spawning controllers.", ) ) declared_arguments.append( DeclareLaunchArgument( "initial_joint_controller", default_value="scaled_joint_trajectory_controller", description="Initially loaded robot controller.", choices=[ "scaled_joint_trajectory_controller", "joint_trajectory_controller", "forward_velocity_controller", "forward_position_controller", ], ) ) declared_arguments.append( DeclareLaunchArgument( "activate_joint_controller", default_value="true", description="Activate loaded joint controller.", ) ) declared_arguments.append( DeclareLaunchArgument("launch_rviz", default_value="false", description="Launch RViz?") ) declared_arguments.append( DeclareLaunchArgument( "launch_dashboard_client", default_value="true", description="Launch Dashboard Client?" ) ) declared_arguments.append( DeclareLaunchArgument( "use_tool_communication", default_value="false", description="Only available for e series!", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_parity", default_value="0", description="Parity configuration for serial communication. Only effective, if \ use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_baud_rate", default_value="115200", description="Baud rate configuration for serial communication. Only effective, if \ use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_stop_bits", default_value="1", description="Stop bits configuration for serial communication. Only effective, if \ use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_rx_idle_chars", default_value="1.5", description="RX idle chars configuration for serial communication. Only effective, \ if use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_tx_idle_chars", default_value="3.5", description="TX idle chars configuration for serial communication. Only effective, \ if use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_device_name", default_value="/tmp/ttyUR", description="File descriptor that will be generated for the tool communication device. \ The user has be be allowed to write to this location. \ Only effective, if use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_tcp_port", default_value="54321", description="Remote port that will be used for bridging the tool's serial device. \ Only effective, if use_tool_communication is set to True.", ) ) declared_arguments.append( DeclareLaunchArgument( "tool_voltage", default_value="0", # 0 being a conservative value that won't destroy anything description="Tool voltage that will be setup.", ) ) declared_arguments.append( DeclareLaunchArgument( "reverse_ip", default_value="0.0.0.0", description="IP that will be used for the robot controller to communicate back to the driver.", ) ) declared_arguments.append( DeclareLaunchArgument( "script_command_port", default_value="50004", description="Port that will be opened to forward script commands from the driver to the robot", ) ) return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)]) ```

Controller config

ur_controllers.yaml only the tf_prefix is different from the original source

see ur_controllers.yaml ``` controller_manager: ros__parameters: joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster io_and_status_controller: type: ur_controllers/GPIOController speed_scaling_state_broadcaster: type: ur_controllers/SpeedScalingStateBroadcaster force_torque_sensor_broadcaster: type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController scaled_joint_trajectory_controller: type: ur_controllers/ScaledJointTrajectoryController forward_velocity_controller: type: velocity_controllers/JointGroupVelocityController forward_position_controller: type: position_controllers/JointGroupPositionController speed_scaling_state_broadcaster: ros__parameters: state_publish_rate: 100.0 tf_prefix: "ur5/" io_and_status_controller: ros__parameters: tf_prefix: "ur5/" force_torque_sensor_broadcaster: ros__parameters: sensor_name: tcp_fts_sensor state_interface_names: - force.x - force.y - force.z - torque.x - torque.y - torque.z frame_id: tool0 topic_name: ft_data joint_trajectory_controller: ros__parameters: joints: - ur5/shoulder_pan_joint - ur5/shoulder_lift_joint - ur5/elbow_joint - ur5/wrist_1_joint - ur5/wrist_2_joint - ur5/wrist_3_joint command_interfaces: - position state_interfaces: - position - velocity state_publish_rate: 100.0 action_monitor_rate: 20.0 allow_partial_joints_goal: false constraints: stopped_velocity_tolerance: 0.2 goal_time: 0.0 ur5/shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } ur5/shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } ur5/elbow_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_1_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_2_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_3_joint: { trajectory: 0.2, goal: 0.1 } scaled_joint_trajectory_controller: ros__parameters: joints: - ur5/shoulder_pan_joint - ur5/shoulder_lift_joint - ur5/elbow_joint - ur5/wrist_1_joint - ur5/wrist_2_joint - ur5/wrist_3_joint command_interfaces: - position state_interfaces: - position - velocity state_publish_rate: 100.0 action_monitor_rate: 20.0 allow_partial_joints_goal: false constraints: stopped_velocity_tolerance: 0.2 goal_time: 0.0 ur5/shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } ur5/shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } ur5/elbow_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_1_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_2_joint: { trajectory: 0.2, goal: 0.1 } ur5/wrist_3_joint: { trajectory: 0.2, goal: 0.1 } speed_scaling_interface_name: speed_scaling/speed_scaling_factor forward_velocity_controller: ros__parameters: joints: - ur5/shoulder_pan_joint - ur5/shoulder_lift_joint - ur5/elbow_joint - ur5/wrist_1_joint - ur5/wrist_2_joint - ur5/wrist_3_joint interface_name: velocity forward_position_controller: ros__parameters: joints: - ur5/shoulder_pan_joint - ur5/shoulder_lift_joint - ur5/elbow_joint - ur5/wrist_1_joint - ur5/wrist_2_joint - ur5/wrist_3_joint ```

@firesurfer you said that this is a ros2_control issue. I'd like to help finding this issue, but I'm unsure where to begin as I'm not familiar with ros2_control. If you maybe have a hint for the search in the upstream ros2_control repo, I could open an issue there and track down the problem. At the minute I just don't know, what to even call the issue in ros2_control.

Thanks for both your efforts!

fmauch commented 1 year ago

@niemsoen just to be clear: The output mentioned above is not a real issue, it is rather unpleasant. The SJTC not getting activated has (most probably) nothing to do with that.

Your controllers config file seems to be missing some tf_prefix adaption. Please see the file we have in #726. You'll also have to prefix the speed_scaling_interface_name (and tcp_fts_sensor to be complete) as your log output states.

Please do not further post in this issue if you keep having problems with startup, since as stated above this is most probably not related to the output.


Edit: Of course: If you keep having problems feel free to open a new issue. I did not want to tell you to not further bother us, I just think it doesn't belong in this issue.

niemsoen commented 1 year ago

@fmauch thank you so much, you made our day. I didn't see the instructions in #726, thanks for pointing it out - now it works!

JaisonJose241 commented 1 year ago

I got the problem solved by building ros2_control from source.

firesurfer commented 1 year ago

@JaisonJose241 Can you tell me which commit you are exactly on. I just digged a bit through the ros2_control master branch and I couldn't find any commit which could explain why this issue doesn't occur when building from source.