Universal_Robots_ROS_Driver
Universal_Robots_ROS_Driver copied to clipboard
hardware_interface error
Summary
Introduction to the issue Dear all, I added a gripper with 2DOF to my ur5e arm. I modified the URDF of the ur5e (ur_macro.xacro) and its transmission file (ur_transmissions.xacro) as well as the moveit config file (ros_controllers.yaml) to include the two additional gripper (gripper_joint_1 and gripper_joint_2). I could control the ur5e arm and the gripper 2DOF in gazebo using movit without any problem or error. However, when I try to launch the ur_robot_driver to control the real gripper and ur5e arm, I get error that it could not find "gripper_joint_1" in 'scaled_controllers::ScaledPositionJointInterface', 'hardware_interface::PositionJointInterface', and 'hardware_interface::VelocityJointInterface'. Can anyone give hint to fix this error. Meanwhile, I also modified the ur_robot_driver config file (ur5e_controllers.yaml).
Versions
- ROS Driver version: Universal_Robots_ROS_Driver
- Ros Distribution: Melodic
- Robot Serial Number:
Logs
sado@sado:~/Desktop/ur5e_driver_ws$ roslaunch ur_robot_driver ur5e_bringup.launch robot_ip:=192.168.100.60 use_tool_communication:=true tool_voltage:=24 kinematics_config:=/home/sado/Desktop/ur5e_driver_ws_6/my_robot_calibration1.yaml ... logging to /home/skikk-deleafing/.ros/log/3e96223e-a47e-11ec-a602-54b203f0c751/roslaunch-skikkdeleafing-18361.log Checking log directory for disk usage. This may take a while. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB.
Using load_yaml() directly is deprecated. Use xacro.load_yaml() instead. Using load_yaml() directly is deprecated. Use xacro.load_yaml() instead. Using load_yaml() directly is deprecated. Use xacro.load_yaml() instead. Using load_yaml() directly is deprecated. Use xacro.load_yaml() instead. started roslaunch server http://192.168.100.96:41467/
PARAMETERS
- /controller_stopper/consistent_controllers: ['joint_state_con...
- /force_torque_sensor_controller/publish_rate: 500
- /force_torque_sensor_controller/type: force_torque_sens...
- /forward_cartesian_traj_controller/joints: ['shoulder_pan_jo...
- /forward_cartesian_traj_controller/type: pass_through_cont...
- /forward_joint_traj_controller/joints: ['shoulder_pan_jo...
- /forward_joint_traj_controller/type: pass_through_cont...
- /hardware_control_loop/loop_hz: 500
- /joint_based_cartesian_traj_controller/base: base
- /joint_based_cartesian_traj_controller/joints: ['shoulder_pan_jo...
- /joint_based_cartesian_traj_controller/tip: tool0
- /joint_based_cartesian_traj_controller/type: position_controll...
- /joint_group_vel_controller/joints: ['shoulder_pan_jo...
- /joint_group_vel_controller/type: velocity_controll...
- /joint_state_controller/publish_rate: 500
- /joint_state_controller/type: joint_state_contr...
- /pos_joint_traj_controller/action_monitor_rate: 20
- /pos_joint_traj_controller/constraints/elbow_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/elbow_joint/trajectory: 0.2
- /pos_joint_traj_controller/constraints/goal_time: 0.6
- /pos_joint_traj_controller/constraints/gripper_joint_1/goal: 0.1
- /pos_joint_traj_controller/constraints/gripper_joint_1/trajectory: 0.2
- /pos_joint_traj_controller/constraints/gripper_joint_2/goal: 0.1
- /pos_joint_traj_controller/constraints/gripper_joint_2/trajectory: 0.2
- /pos_joint_traj_controller/constraints/shoulder_lift_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/shoulder_lift_joint/trajectory: 0.2
- /pos_joint_traj_controller/constraints/shoulder_pan_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/shoulder_pan_joint/trajectory: 0.2
- /pos_joint_traj_controller/constraints/stopped_velocity_tolerance: 0.05
- /pos_joint_traj_controller/constraints/wrist_1_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/wrist_1_joint/trajectory: 0.2
- /pos_joint_traj_controller/constraints/wrist_2_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/wrist_2_joint/trajectory: 0.2
- /pos_joint_traj_controller/constraints/wrist_3_joint/goal: 0.1
- /pos_joint_traj_controller/constraints/wrist_3_joint/trajectory: 0.2
- /pos_joint_traj_controller/joints: ['shoulder_pan_jo...
- /pos_joint_traj_controller/state_publish_rate: 500
- /pos_joint_traj_controller/stop_trajectory_duration: 0.5
- /pos_joint_traj_controller/type: position_controll...
- /pose_based_cartesian_traj_controller/base: base
- /pose_based_cartesian_traj_controller/joints: ['shoulder_pan_jo...
- /pose_based_cartesian_traj_controller/tip: tool0_controller
- /pose_based_cartesian_traj_controller/type: pose_controllers/...
- /robot_description: <?xml version="1....
- /robot_status_controller/handle_name: industrial_robot_...
- /robot_status_controller/publish_rate: 10
- /robot_status_controller/type: industrial_robot_...
- /rosdistro: melodic
- /rosversion: 1.14.12
- /scaled_pos_joint_traj_controller/action_monitor_rate: 20
- /scaled_pos_joint_traj_controller/constraints/elbow_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/elbow_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/goal_time: 0.6
- /scaled_pos_joint_traj_controller/constraints/gripper_joint_1/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/gripper_joint_1/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/gripper_joint_2/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/gripper_joint_2/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/shoulder_lift_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/shoulder_lift_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/shoulder_pan_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/shoulder_pan_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/stopped_velocity_tolerance: 0.05
- /scaled_pos_joint_traj_controller/constraints/wrist_1_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/wrist_1_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/wrist_2_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/wrist_2_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/constraints/wrist_3_joint/goal: 0.1
- /scaled_pos_joint_traj_controller/constraints/wrist_3_joint/trajectory: 0.2
- /scaled_pos_joint_traj_controller/joints: ['shoulder_pan_jo...
- /scaled_pos_joint_traj_controller/state_publish_rate: 500
- /scaled_pos_joint_traj_controller/stop_trajectory_duration: 0.5
- /scaled_pos_joint_traj_controller/type: position_controll...
- /scaled_vel_joint_traj_controller/action_monitor_rate: 20
- /scaled_vel_joint_traj_controller/constraints/elbow_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/elbow_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/goal_time: 0.6
- /scaled_vel_joint_traj_controller/constraints/gripper_joint_1/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/gripper_joint_1/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/gripper_joint_2/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/gripper_joint_2/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/shoulder_lift_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/shoulder_lift_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/shoulder_pan_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/shoulder_pan_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/stopped_velocity_tolerance: 0.05
- /scaled_vel_joint_traj_controller/constraints/wrist_1_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/wrist_1_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/wrist_2_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/wrist_2_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/constraints/wrist_3_joint/goal: 0.1
- /scaled_vel_joint_traj_controller/constraints/wrist_3_joint/trajectory: 0.1
- /scaled_vel_joint_traj_controller/gains/elbow_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/elbow_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/elbow_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/elbow_joint/p: 5.0
- /scaled_vel_joint_traj_controller/gains/gripper_joint_1/d: 0.1
- /scaled_vel_joint_traj_controller/gains/gripper_joint_1/i: 0.05
- /scaled_vel_joint_traj_controller/gains/gripper_joint_1/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/gripper_joint_1/p: 5.0
- /scaled_vel_joint_traj_controller/gains/gripper_joint_2/d: 0.1
- /scaled_vel_joint_traj_controller/gains/gripper_joint_2/i: 0.05
- /scaled_vel_joint_traj_controller/gains/gripper_joint_2/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/gripper_joint_2/p: 5.0
- /scaled_vel_joint_traj_controller/gains/shoulder_lift_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/shoulder_lift_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/shoulder_lift_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/shoulder_lift_joint/p: 5.0
- /scaled_vel_joint_traj_controller/gains/shoulder_pan_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/shoulder_pan_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/shoulder_pan_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/shoulder_pan_joint/p: 5.0
- /scaled_vel_joint_traj_controller/gains/wrist_1_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/wrist_1_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/wrist_1_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/wrist_1_joint/p: 5.0
- /scaled_vel_joint_traj_controller/gains/wrist_2_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/wrist_2_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/wrist_2_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/wrist_2_joint/p: 5.0
- /scaled_vel_joint_traj_controller/gains/wrist_3_joint/d: 0.1
- /scaled_vel_joint_traj_controller/gains/wrist_3_joint/i: 0.05
- /scaled_vel_joint_traj_controller/gains/wrist_3_joint/i_clamp: 1
- /scaled_vel_joint_traj_controller/gains/wrist_3_joint/p: 5.0
- /scaled_vel_joint_traj_controller/joints: ['shoulder_pan_jo...
- /scaled_vel_joint_traj_controller/state_publish_rate: 500
- /scaled_vel_joint_traj_controller/stop_trajectory_duration: 0.5
- /scaled_vel_joint_traj_controller/type: velocity_controll...
- /scaled_vel_joint_traj_controller/velocity_ff/elbow_joint: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/gripper_joint_1: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/gripper_joint_2: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/shoulder_lift_joint: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/shoulder_pan_joint: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/wrist_1_joint: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/wrist_2_joint: 1.0
- /scaled_vel_joint_traj_controller/velocity_ff/wrist_3_joint: 1.0
- /speed_scaling_state_controller/publish_rate: 500
- /speed_scaling_state_controller/type: scaled_controller...
- /twist_controller/frame_id: tool0_controller
- /twist_controller/joints: ['shoulder_pan_jo...
- /twist_controller/publish_rate: 500
- /twist_controller/type: ros_controllers_c...
- /ur_hardware_interface/headless_mode: False
- /ur_hardware_interface/input_recipe_file: /home/skikk-delea...
- /ur_hardware_interface/joints: ['shoulder_pan_jo...
- /ur_hardware_interface/kinematics/forearm/pitch: -0.000507644907308
- /ur_hardware_interface/kinematics/forearm/roll: 0.000265362989289
- /ur_hardware_interface/kinematics/forearm/x: -0.425047301956
- /ur_hardware_interface/kinematics/forearm/y: 0
- /ur_hardware_interface/kinematics/forearm/yaw: 6.075807873e-07
- /ur_hardware_interface/kinematics/forearm/z: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/pitch: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/roll: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/x: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/y: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/yaw: 0
- /ur_hardware_interface/kinematics/gripper_joint_1/z: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/pitch: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/roll: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/x: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/y: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/yaw: 0
- /ur_hardware_interface/kinematics/gripper_joint_2/z: 0
- /ur_hardware_interface/kinematics/hash: calib_15749631837...
- /ur_hardware_interface/kinematics/shoulder/pitch: 0
- /ur_hardware_interface/kinematics/shoulder/roll: 0
- /ur_hardware_interface/kinematics/shoulder/x: 0
- /ur_hardware_interface/kinematics/shoulder/y: 0
- /ur_hardware_interface/kinematics/shoulder/yaw: 1.91471563743e-08
- /ur_hardware_interface/kinematics/shoulder/z: 0.162778846868
- /ur_hardware_interface/kinematics/upper_arm/pitch: 0
- /ur_hardware_interface/kinematics/upper_arm/roll: 1.57110589325
- /ur_hardware_interface/kinematics/upper_arm/x: 0.000173486186267
- /ur_hardware_interface/kinematics/upper_arm/y: 0
- /ur_hardware_interface/kinematics/upper_arm/yaw: -1.35621555138e-06
- /ur_hardware_interface/kinematics/upper_arm/z: 0
- /ur_hardware_interface/kinematics/wrist_1/pitch: 0.000395234553489
- /ur_hardware_interface/kinematics/wrist_1/roll: 0.00570052805542
- /ur_hardware_interface/kinematics/wrist_1/x: -0.392190977785
- /ur_hardware_interface/kinematics/wrist_1/y: -0.000762015258837
- /ur_hardware_interface/kinematics/wrist_1/yaw: -1.10380368897e-06
- /ur_hardware_interface/kinematics/wrist_1/z: 0.133673055769
- /ur_hardware_interface/kinematics/wrist_2/pitch: 0
- /ur_hardware_interface/kinematics/wrist_2/roll: 1.57169961237
- /ur_hardware_interface/kinematics/wrist_2/x: 0.00015171180519
- /ur_hardware_interface/kinematics/wrist_2/y: -0.0995844269728
- /ur_hardware_interface/kinematics/wrist_2/yaw: -2.5877206876e-08
- /ur_hardware_interface/kinematics/wrist_2/z: -8.99532008373e-05
- /ur_hardware_interface/kinematics/wrist_3/pitch: 3.14159265359
- /ur_hardware_interface/kinematics/wrist_3/roll: 1.57229273421
- /ur_hardware_interface/kinematics/wrist_3/x: 3.70749059688e-05
- /ur_hardware_interface/kinematics/wrist_3/y: 0.099554697055
- /ur_hardware_interface/kinematics/wrist_3/yaw: 3.14159258399
- /ur_hardware_interface/kinematics/wrist_3/z: 0.000148974497776
- /ur_hardware_interface/output_recipe_file: /home/skikk-delea...
- /ur_hardware_interface/reverse_ip:
- /ur_hardware_interface/reverse_port: 50001
- /ur_hardware_interface/robot_ip: 192.168.100.60
- /ur_hardware_interface/script_file: /opt/ros/melodic/...
- /ur_hardware_interface/script_sender_port: 50002
- /ur_hardware_interface/servoj_gain: 2000
- /ur_hardware_interface/servoj_lookahead_time: 0.03
- /ur_hardware_interface/tf_prefix:
- /ur_hardware_interface/tool_baud_rate: 115200
- /ur_hardware_interface/tool_parity: 0
- /ur_hardware_interface/tool_rx_idle_chars: 1.5
- /ur_hardware_interface/tool_stop_bits: 1
- /ur_hardware_interface/tool_tx_idle_chars: 3.5
- /ur_hardware_interface/tool_voltage: 24
- /ur_hardware_interface/trajectory_port: 50003
- /ur_hardware_interface/use_tool_communication: True
- /ur_tool_communication_bridge/device_name: /tmp/ttyUR
- /ur_tool_communication_bridge/reverse_ip:
- /ur_tool_communication_bridge/reverse_port: 50001
- /ur_tool_communication_bridge/robot_ip: 192.168.100.60
- /ur_tool_communication_bridge/script_sender_port: 50002
- /ur_tool_communication_bridge/tcp_port: 54321
- /vel_joint_traj_controller/action_monitor_rate: 20
- /vel_joint_traj_controller/constraints/elbow_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/elbow_joint/trajectory: 0.1
- /vel_joint_traj_controller/constraints/goal_time: 0.6
- /vel_joint_traj_controller/constraints/gripper_joint_1/goal: 0.1
- /vel_joint_traj_controller/constraints/gripper_joint_1/trajectory: 0.1
- /vel_joint_traj_controller/constraints/gripper_joint_2/goal: 0.1
- /vel_joint_traj_controller/constraints/gripper_joint_2/trajectory: 0.1
- /vel_joint_traj_controller/constraints/shoulder_lift_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/shoulder_lift_joint/trajectory: 0.1
- /vel_joint_traj_controller/constraints/shoulder_pan_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/shoulder_pan_joint/trajectory: 0.1
- /vel_joint_traj_controller/constraints/stopped_velocity_tolerance: 0.05
- /vel_joint_traj_controller/constraints/wrist_1_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/wrist_1_joint/trajectory: 0.1
- /vel_joint_traj_controller/constraints/wrist_2_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/wrist_2_joint/trajectory: 0.1
- /vel_joint_traj_controller/constraints/wrist_3_joint/goal: 0.1
- /vel_joint_traj_controller/constraints/wrist_3_joint/trajectory: 0.1
- /vel_joint_traj_controller/gains/elbow_joint/d: 0.1
- /vel_joint_traj_controller/gains/elbow_joint/i: 0.05
- /vel_joint_traj_controller/gains/elbow_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/elbow_joint/p: 5.0
- /vel_joint_traj_controller/gains/gripper_joint_1/d: 0.1
- /vel_joint_traj_controller/gains/gripper_joint_1/i: 0.05
- /vel_joint_traj_controller/gains/gripper_joint_1/i_clamp: 1
- /vel_joint_traj_controller/gains/gripper_joint_1/p: 5.0
- /vel_joint_traj_controller/gains/gripper_joint_2/d: 0.1
- /vel_joint_traj_controller/gains/gripper_joint_2/i: 0.05
- /vel_joint_traj_controller/gains/gripper_joint_2/i_clamp: 1
- /vel_joint_traj_controller/gains/gripper_joint_2/p: 5.0
- /vel_joint_traj_controller/gains/shoulder_lift_joint/d: 0.1
- /vel_joint_traj_controller/gains/shoulder_lift_joint/i: 0.05
- /vel_joint_traj_controller/gains/shoulder_lift_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/shoulder_lift_joint/p: 5.0
- /vel_joint_traj_controller/gains/shoulder_pan_joint/d: 0.1
- /vel_joint_traj_controller/gains/shoulder_pan_joint/i: 0.05
- /vel_joint_traj_controller/gains/shoulder_pan_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/shoulder_pan_joint/p: 5.0
- /vel_joint_traj_controller/gains/wrist_1_joint/d: 0.1
- /vel_joint_traj_controller/gains/wrist_1_joint/i: 0.05
- /vel_joint_traj_controller/gains/wrist_1_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/wrist_1_joint/p: 5.0
- /vel_joint_traj_controller/gains/wrist_2_joint/d: 0.1
- /vel_joint_traj_controller/gains/wrist_2_joint/i: 0.05
- /vel_joint_traj_controller/gains/wrist_2_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/wrist_2_joint/p: 5.0
- /vel_joint_traj_controller/gains/wrist_3_joint/d: 0.1
- /vel_joint_traj_controller/gains/wrist_3_joint/i: 0.05
- /vel_joint_traj_controller/gains/wrist_3_joint/i_clamp: 1
- /vel_joint_traj_controller/gains/wrist_3_joint/p: 5.0
- /vel_joint_traj_controller/joints: ['shoulder_pan_jo...
- /vel_joint_traj_controller/state_publish_rate: 500
- /vel_joint_traj_controller/stop_trajectory_duration: 0.5
- /vel_joint_traj_controller/type: velocity_controll...
- /vel_joint_traj_controller/velocity_ff/elbow_joint: 1.0
- /vel_joint_traj_controller/velocity_ff/gripper_joint_1: 1.0
- /vel_joint_traj_controller/velocity_ff/gripper_joint_2: 1.0
- /vel_joint_traj_controller/velocity_ff/shoulder_lift_joint: 1.0
- /vel_joint_traj_controller/velocity_ff/shoulder_pan_joint: 1.0
- /vel_joint_traj_controller/velocity_ff/wrist_1_joint: 1.0
- /vel_joint_traj_controller/velocity_ff/wrist_2_joint: 1.0
- /vel_joint_traj_controller/velocity_ff/wrist_3_joint: 1.0
NODES / controller_stopper (controller_stopper/node) robot_state_publisher (robot_state_publisher/robot_state_publisher) ros_control_controller_spawner (controller_manager/spawner) ros_control_stopped_spawner (controller_manager/spawner) ur_hardware_interface (ur_robot_driver/ur_robot_driver_node) ur_tool_communication_bridge (ur_robot_driver/tool_communication) /ur_hardware_interface/ ur_robot_state_helper (ur_robot_driver/robot_state_helper)
auto-starting new master process[master]: started with pid [18380] ROS_MASTER_URI=http://localhost:11311
setting /run_id to 3e96223e-a47e-11ec-a602-54b203f0c751 process[rosout-1]: started with pid [18394] started core service [/rosout] process[robot_state_publisher-2]: started with pid [18401] process[ur_hardware_interface-3]: started with pid [18402] process[ur_tool_communication_bridge-4]: started with pid [18403] process[ros_control_controller_spawner-5]: started with pid [18410] process[ros_control_stopped_spawner-6]: started with pid [18414] process[controller_stopper-7]: started with pid [18418] [ INFO] [1647362268.068948313]: Initializing dashboard client process[ur_hardware_interface/ur_robot_state_helper-8]: started with pid [18420] [ INFO] [1647362268.071656714]: Connected: Universal Robots Dashboard Server
[ INFO] [1647362268.078649719]: Initializing urdriver [ WARN] [1647362268.085830777]: No realtime capabilities found. Consider using a realtime system for better performance [ INFO] [1647362268.088182397]: Waiting for controller manager service to come up on /controller_manager/switch_controller [ INFO] [1647362268.089019336]: waitForService: Service [/controller_manager/switch_controller] has not been advertised, waiting... [ INFO] [1647362268.355331928]: Negotiated RTDE protocol version to 2. [ INFO] [1647362268.355732467]: Setting up RTDE communication with frequency 500.000000 [INFO] [1647362268.370312]: Controller Spawner: Waiting for service controller_manager/load_controller [INFO] [1647362268.452539]: Remote device is available at '/tmp/ttyUR' [INFO] [1647362268.453667]: Starting socat with following command: socat pty,link=/tmp/ttyUR,raw,ignoreeof,waitslave tcp:192.168.100.60:54321 [INFO] [1647362268.475854]: Controller Spawner: Waiting for service controller_manager/load_controller [ INFO] [1647362269.374269838]: Checking if calibration data matches connected robot. [ WARN] [1647362269.374700162]: No realtime capabilities found. Consider using a realtime system for better performance [ INFO] [1647362270.441081712]: Calibration checked successfully. [ WARN] [1647362270.448042240]: No realtime capabilities found. Consider using a realtime system for better performance [ INFO] [1647362270.448258523]: Loaded ur_robot_driver hardware_interface [ INFO] [1647362270.476336628]: waitForService: Service [/controller_manager/switch_controller] is now available. [ INFO] [1647362270.476363501]: Service available. [ INFO] [1647362270.476377597]: Waiting for controller list service to come up on /controller_manager/list_controllers [ INFO] [1647362270.476763604]: Service available. [INFO] [1647362270.480600]: Controller Spawner: Waiting for service controller_manager/switch_controller [INFO] [1647362270.482535]: Controller Spawner: Waiting for service controller_manager/unload_controller [INFO] [1647362270.484089]: Loading controller: joint_state_controller [INFO] [1647362270.487969]: Loading controller: scaled_pos_joint_traj_controller [ERROR] [1647362270.495553934]: Could not find joint 'gripper_joint_1' in 'scaled_controllers::ScaledPositionJointInterface'. [ERROR] [1647362270.495607754]: Failed to initialize the controller [ERROR] [1647362270.495642768]: Initializing controller 'scaled_pos_joint_traj_controller' failed [INFO] [1647362270.586098]: Controller Spawner: Waiting for service controller_manager/switch_controller [INFO] [1647362270.589152]: Controller Spawner: Waiting for service controller_manager/unload_controller [INFO] [1647362270.591911]: Loading controller: pos_joint_traj_controller [ERROR] [1647362270.602989686]: Could not find joint 'gripper_joint_1' in 'hardware_interface::PositionJointInterface'. [ERROR] [1647362270.603067824]: Failed to initialize the controller [ERROR] [1647362270.603091016]: Initializing controller 'pos_joint_traj_controller' failed [ INFO] [1647362270.663927745]: Robot's safety mode is now NORMAL [ INFO] [1647362270.664682384]: Robot mode is now POWER_OFF [ERROR] [1647362271.496768]: Failed to load scaled_pos_joint_traj_controller [INFO] [1647362271.498336]: Loading controller: speed_scaling_state_controller [INFO] [1647362271.504177]: Loading controller: force_torque_sensor_controller [INFO] [1647362271.510231]: Controller Spawner: Loaded controllers: joint_state_controller, speed_scaling_state_controller, force_torque_sensor_controller [INFO] [1647362271.514166]: Started controllers: joint_state_controller, speed_scaling_state_controller, force_torque_sensor_controller [ERROR] [1647362271.604405]: Failed to load pos_joint_traj_controller [INFO] [1647362271.605655]: Loading controller: joint_group_vel_controller [ERROR] [1647362271.609484062]: Exception thrown: Could not find resource 'gripper_joint_1' in 'hardware_interface::VelocityJointInterface'. [ERROR] [1647362271.609525471]: Failed to initialize the controller [ERROR] [1647362271.609551139]: Initializing controller 'joint_group_vel_controller' failed [ERROR] [1647362272.610713]: Failed to load joint_group_vel_controller [INFO] [1647362272.612180]: Controller Spawner: Loaded controllers:
You will need a driver for your gripper, this is nothing the ur_robot_driver will do for you.
If you take a look at the ros_control
documentation there usually is a controller_manager, a hardware_interface and controllers forming up a working robot. The hardware interface is an abstraction of the specific hardware to a set of common interfaces (e.g. reading / writing joint values). What we call a "driver" in this context is a node having a (or multiple) hardware interface(s) and a controller_manager. See driver's main node as an example.
Solution 1: ros_control + combined hardware interface
So, in order to include your gripper into that control structure, you'll need a hardware interface for your gripper. I don't expect that you can control the two joints individually, though, usually with 2F-grippers there is only one joint that can be controlled and the others follow by mechanical constraints. URDF offers to model this e.g. through so called mimic joints.
So, in order to include the gripper into your URDF properly, you should create a standalone description of your gripper (if there is not already one out there) that reflects the actual hardware (e.g. controllable joint, mimic joints, etc.). With this, you would assemble a description that uses the UR description and your gripper description. Do not modify the ur_macro.xacro
file unless you really want to change your UR robot's description!
Once you have a proper description and a hardware interface for your gripper, you can assemble both hardware interfaces into one driver node. Se this example on how to do that.
On this driver node you can define controllers that span over different hardware interface's joints. However, this is limited to joints with a common interface. For example, grippers often only offer an interface to go to a target position and the gripper interpolates the way to that target position. Sending position commands in high frequency is often not supported. Hence, it is questionable, whether creating a combined HW interface is even an option you would like to consider.
Option 2: standalone driver
A better option might be to write (or use an existing) individual driver node for your gripper. Those will usually implement talking to the gripper, offering interfaces to send commands to the gripper and also publish a joint state for your gripper.
With this, it would be sufficient to extend the robot's description as explained in option 1 and start the standalone gripper driver. The joint_state published by that driver will be picked up by the robot_state_publisher and your TF tree will be updated automatically.
As an addendum: You Gazebo setup worked, as gazebo creates a hardware interface from all joints found in your URDF. As on that level a joint is merely a black box with a dynamic value, this works fine. However, as elaborated above, in the real world things aren't that simple.
I hope, this helps!
This issue has not been updated for a long time. If no further updates are added, this will be closed automatically. Comment on the issue to prevent automatic closing.
This issue has been closed due to inactivity. Feel free to comment or reopen if this is still relevant.