UniversalRobots / Universal_Robots_ROS2_Driver

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

Strange DH Parameters Obtained During UR Robot Calibration #1047

Open Liu-Jinxin opened 4 days ago

Liu-Jinxin commented 4 days ago

Affected ROS2 Driver version(s)

Humble and Noetic

Used ROS distribution.

Humble, Other

Which combination of platform is the ROS driver running on.

Ubuntu Linux with standard kernel

How is the UR ROS2 Driver installed.

Build both the ROS driver and UR Client Library from source

Which robot platform is the driver connected to.

UR E-series robot

Robot SW / URSim version(s)

UR5e

How is the ROS driver used.

Through the robot teach pendant using External Control URCap

Issue details

Summary

I am experiencing a recurring issue with obtaining unexpected 'dh_d' parameter in Denavit-Hartenberg (DH) parameters during the calibration of a UR robot. This problem persists across two different ROS distributions: ROS 2 Humble and ROS Noetic. I followed the standard calibration procedures recommended for each distribution, but the parameters outputted remain unusual and not typical for UR robots.

Could anyone help in identifying the root cause of these strange parameter values or provide guidance on potential fixes? Below are the details of the process I followed and the abnormal DH parameters I've encountered:

Issue details

ROS2 Humble output

ros2 launch ur_calibration calibration_correction.launch.py \
robot_ip:=192.168.1.102 target_filename:="${HOME}/my_robot_calibration.yaml"
[INFO] [launch]: All log files can be found below /home/jinxin/.ros/log/2024-07-03-21-22-52-224758-jinxin-NUC11PAHi7-1451099
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [calibration_correction-1]: process started with pid [1451100]
[calibration_correction-1] [WARN] [1720012972.271941632] [UR_Client_Library:]: Failed to read from stream, reconnecting in 1 seconds...
[calibration_correction-1] [INFO] [1720012973.329693979] [ur_calibration]: checksum: [2825181143 3042558272 2822691188 2835687819 2834801219 2836969508 ]
[calibration_correction-1] dh_theta: [-3.56924382237389e-08 -0.2072967299171 0.241669808564682 -0.0343661586484612 7.61729097889866e-07 2.02321519607307e-08 ]
[calibration_correction-1] dh_a: [0.000111693463493609 -0.416125972469429 -0.392140204552388 -0.000108907036770274 9.43516716160648e-05 0 ]
[calibration_correction-1] dh_d: [0.162665605346122 97.189910532292 -94.9711602844417 -2.08508702707816 0.0997642283617711 0.0995620646733148 ]
[calibration_correction-1] dh_alpha: [1.5698300612413 -0.000900510510120333 0.00607655398363128 1.57051936520464 -1.57150768772091 0 ]
[calibration_correction-1] calibration_status: 2
[calibration_correction-1] 
[calibration_correction-1] [INFO] [1720012973.430293383] [ur_calibration]: Writing calibration data to "/home/jinxin/my_robot_calibration.yaml"
[calibration_correction-1] [INFO] [1720012973.430622046] [ur_calibration]: Wrote output.
[calibration_correction-1] [INFO] [1720012973.430696423] [ur_calibration]: Calibration correction done
[INFO] [calibration_correction-1]: process has finished cleanly [pid 1451100]

ROS Noetic Output

roslaunch ur_calibration calibration_correction.launch robot_ip:=192.168.1.102 target_filename:="my_robot_calibration.yaml"
... logging to /home/jinxin/.ros/log/b1c48684-3940-11ef-8b75-27178cebc286/roslaunch-jinxin-ur20-385340.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.

started roslaunch server http://jinxin-ur20:46691/

SUMMARY
========

PARAMETERS
 * /calibration_correction/output_filename: my_robot_calibrat...
 * /calibration_correction/robot_ip: 192.168.1.102
 * /rosdistro: noetic
 * /rosversion: 1.16.0

NODES
  /
    calibration_correction (ur_calibration/calibration_correction)

auto-starting new master
process[master]: started with pid [385354]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to b1c48684-3940-11ef-8b75-27178cebc286
process[rosout-1]: started with pid [385364]
started core service [/rosout]
process[calibration_correction-2]: started with pid [385367]
[ WARN] [1720013549.902573288]: Failed to read from stream, reconnecting in 1 seconds...
[ INFO] [1720013551.480856718]: checksum: [2825181143 3042558272 2822691188 2835687819 2834801219 2836969508 ]
dh_theta: [-3.56924382237389e-08 -0.2072967299171 0.241669808564682 -0.0343661586484612 7.61729097889866e-07 2.02321519607307e-08 ]
dh_a: [0.000111693463493609 -0.416125972469429 -0.392140204552388 -0.000108907036770274 9.43516716160648e-05 0 ]
dh_d: [0.162665605346122 97.189910532292 -94.9711602844417 -2.08508702707816 0.0997642283617711 0.0995620646733148 ]
dh_alpha: [1.5698300612413 -0.000900510510120333 0.00607655398363128 1.57051936520464 -1.57150768772091 0 ]
calibration_status: 2

[ INFO] [1720013551.580984867]: Writing calibration data to "/home/jinxin/.ros/my_robot_calibration.yaml"
[ WARN] [1720013551.581013255]: Output file my_robot_calibration.yaml already exists. Overwriting.
[ INFO] [1720013551.581300529]: Wrote output.
[ INFO] [1720013551.581363421]: Calibration correction done
[calibration_correction-2] process has finished cleanly
log file: /home/jinxin/.ros/log/b1c48684-3940-11ef-8b75-27178cebc286/calibration_correction-2*.log

Relevant log output

The humble yaml file is
‵‵`bash
kinematics:
  shoulder:
    x: 0
    y: 0
    z: 0.16266560534612179
    roll: -0
    pitch: 0
    yaw: -3.5692438223738909e-08
  upper_arm:
    x: 0.00011169346349360907
    y: 0
    z: 0
    roll: 1.5698300612412963
    pitch: 0
    yaw: 4.1034599560736544e-06
  forearm:
    x: -0.42523014158330874
    y: 0
    z: 0
    roll: 3.1407114229822017
    pitch: 3.1414073111932037
    yaw: -3.1415925590630103
  wrist_1:
    x: -0.39234399562493477
    y: -0.00081221521355454593
    z: 0.13374112265479854
    roll: 0.006072965534673706
    pitch: 0.00020880245840400782
    yaw: 2.1696500652406749e-06
  wrist_2:
    x: -0.00010890703677027398
    y: -0.099764224535427729
    z: 2.7630858984763806e-05
    roll: 1.5705193652046379
    pitch: 0
    yaw: 7.6172909788986564e-07
  wrist_3:
    x: 9.4351671616064824e-05
    y: 0.099562039482402651
    z: -7.0824556548755905e-05
    roll: 1.5700849658688809
    pitch: 3.1415926535897931
    yaw: -3.1415926333576412
  hash: calib_17372074311215810199

The noetic yaml file is

kinematics:
  shoulder:
    x: 0
    y: 0
    z: 0.1626656053461218
    roll: -0
    pitch: 0
    yaw: -3.569243822373891e-08
  upper_arm:
    x: 0.0001116934634936091
    y: 0
    z: 0
    roll: 1.569830061241296
    pitch: 0
    yaw: 4.103459956073654e-06
  forearm:
    x: -0.4252301415833087
    y: 0
    z: 0
    roll: 3.140711422982202
    pitch: 3.141407311193204
    yaw: -3.14159255906301
  wrist_1:
    x: -0.3923439956249348
    y: -0.0008122152135545459
    z: 0.1337411226547985
    roll: 0.006072965534673706
    pitch: 0.0002088024584040078
    yaw: 2.169650065240675e-06
  wrist_2:
    x: -0.000108907036770274
    y: -0.09976422453542773
    z: 2.763085898476381e-05
    roll: 1.570519365204638
    pitch: 0
    yaw: 7.617290978898656e-07
  wrist_3:
    x: 9.435167161606482e-05
    y: 0.09956203948240265
    z: -7.08245565487559e-05
    roll: 1.570084965868881
    pitch: 3.141592653589793
    yaw: -3.141592633357641
  hash: calib_17372074311215810199


### Accept Public visibility

- [X] I agree to make this context public
Liu-Jinxin commented 3 days ago

When I launch the ur_driver, I have the following output

➜  ur_ws roslaunch ur_robot_driver ur5e_bringup.launch robot_ip:=192.168.1.102                                                       
... logging to /home/jinxin/.ros/log/263d4b1a-39d0-11ef-9f5e-7dcd7b292e3f/roslaunch-jinxin-ur20-5981.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.

started roslaunch server http://jinxin-ur20:40459/

SUMMARY
========

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/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: noetic
 * /rosversion: 1.16.0
 * /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/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/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/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/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/jinxin/ur_w...
 * /ur_hardware_interface/joints: ['shoulder_pan_jo...
 * /ur_hardware_interface/kinematics/forearm/pitch: 0
 * /ur_hardware_interface/kinematics/forearm/roll: 0
 * /ur_hardware_interface/kinematics/forearm/x: -0.425
 * /ur_hardware_interface/kinematics/forearm/y: 0
 * /ur_hardware_interface/kinematics/forearm/yaw: 0
 * /ur_hardware_interface/kinematics/forearm/z: 0
 * /ur_hardware_interface/kinematics/hash: calib_12788084448...
 * /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: 0
 * /ur_hardware_interface/kinematics/shoulder/z: 0.1625
 * /ur_hardware_interface/kinematics/upper_arm/pitch: 0
 * /ur_hardware_interface/kinematics/upper_arm/roll: 1.570796327
 * /ur_hardware_interface/kinematics/upper_arm/x: 0
 * /ur_hardware_interface/kinematics/upper_arm/y: 0
 * /ur_hardware_interface/kinematics/upper_arm/yaw: 0
 * /ur_hardware_interface/kinematics/upper_arm/z: 0
 * /ur_hardware_interface/kinematics/wrist_1/pitch: 0
 * /ur_hardware_interface/kinematics/wrist_1/roll: 0
 * /ur_hardware_interface/kinematics/wrist_1/x: -0.3922
 * /ur_hardware_interface/kinematics/wrist_1/y: 0
 * /ur_hardware_interface/kinematics/wrist_1/yaw: 0
 * /ur_hardware_interface/kinematics/wrist_1/z: 0.1333
 * /ur_hardware_interface/kinematics/wrist_2/pitch: 0
 * /ur_hardware_interface/kinematics/wrist_2/roll: 1.570796327
 * /ur_hardware_interface/kinematics/wrist_2/x: 0
 * /ur_hardware_interface/kinematics/wrist_2/y: -0.0997
 * /ur_hardware_interface/kinematics/wrist_2/yaw: 0
 * /ur_hardware_interface/kinematics/wrist_2/z: -2.04488118229785...
 * /ur_hardware_interface/kinematics/wrist_3/pitch: 3.141592653589793
 * /ur_hardware_interface/kinematics/wrist_3/roll: 1.570796326589793
 * /ur_hardware_interface/kinematics/wrist_3/x: 0
 * /ur_hardware_interface/kinematics/wrist_3/y: 0.0996
 * /ur_hardware_interface/kinematics/wrist_3/yaw: 3.141592653589793
 * /ur_hardware_interface/kinematics/wrist_3/z: -2.04283014801269...
 * /ur_hardware_interface/output_recipe_file: /home/jinxin/ur_w...
 * /ur_hardware_interface/reverse_ip: 
 * /ur_hardware_interface/reverse_port: 50001
 * /ur_hardware_interface/robot_ip: 192.168.1.102
 * /ur_hardware_interface/script_command_port: 50004
 * /ur_hardware_interface/script_file: /opt/ros/noetic/s...
 * /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: 0
 * /ur_hardware_interface/trajectory_port: 50003
 * /ur_hardware_interface/use_spline_interpolation: True
 * /ur_hardware_interface/use_tool_communication: False
 * /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/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/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/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 (ur_robot_driver/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_hardware_interface/
    ur_robot_state_helper (ur_robot_driver/robot_state_helper)

auto-starting new master
process[master]: started with pid [5996]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 263d4b1a-39d0-11ef-9f5e-7dcd7b292e3f
process[rosout-1]: started with pid [6006]
started core service [/rosout]
process[robot_state_publisher-2]: started with pid [6013]
process[ur_hardware_interface-3]: started with pid [6014]
process[ros_control_controller_spawner-4]: started with pid [6015]
process[ros_control_stopped_spawner-5]: started with pid [6016]
process[controller_stopper-6]: started with pid [6017]
process[ur_hardware_interface/ur_robot_state_helper-7]: started with pid [6018]
[ INFO] [1720075163.601970371]: Waiting for controller manager service to come up on /controller_manager/switch_controller
[ INFO] [1720075163.604634746]: waitForService: Service [/controller_manager/switch_controller] has not been advertised, waiting...
[ INFO] [1720075163.611697372]: waitForService: Service [/ur_hardware_interface/dashboard/play] has not been advertised, waiting...
[ INFO] [1720075163.613160862]: Initializing dashboard client
[ INFO] [1720075163.626398397]: Connected: Universal Robots Dashboard Server

[ INFO] [1720075163.652889060]: Initializing urdriver
[ INFO] [1720075163.654046826]: waitForService: Service [/ur_hardware_interface/dashboard/play] is now available.
[ WARN] [1720075163.654230484]: Your system/user seems not to be setup for FIFO scheduling. We recommend using a lowlatency kernel with FIFO scheduling. See https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/blob/master/ur_robot_driver/doc/real_time.md for details.
[ INFO] [1720075163.796426567]: Negotiated RTDE protocol version to 2.
[ INFO] [1720075163.797134440]: Setting up RTDE communication with frequency 500.000000
[INFO] [1720075163.860539]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1720075163.861286]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1720075164.812797217]: Checking if calibration data matches connected robot.
[ERROR] [1720075165.887589851]: The calibration parameters of the connected robot don't match the ones from the given kinematics config file. Please be aware that this can lead to critical inaccuracies of tcp positions. Use the ur_calibration tool to extract the correct calibration from the robot and pass that into the description. See [https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#extract-calibration-information] for details.
[ WARN] [1720075165.901897341]: Your system/user seems not to be setup for FIFO scheduling. We recommend using a lowlatency kernel with FIFO scheduling. See https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/blob/master/ur_robot_driver/doc/real_time.md for details.
[ INFO] [1720075165.902423546]: Loaded ur_robot_driver hardware_interface
[ INFO] [1720075165.931026142]: waitForService: Service [/controller_manager/switch_controller] is now available.
[ INFO] [1720075165.931044049]: Service available.
[ INFO] [1720075165.931053056]: Waiting for controller list service to come up on /controller_manager/list_controllers
[ INFO] [1720075165.931566854]: Service available.
[INFO] [1720075165.975991]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1720075165.976321]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1720075165.977597]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1720075165.977938]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1720075165.978960]: Loading controller: joint_state_controller
[INFO] [1720075165.979332]: Loading controller: pos_joint_traj_controller
[INFO] [1720075165.984957]: Loading controller: scaled_pos_joint_traj_controller
[INFO] [1720075165.999009]: Loading controller: joint_group_vel_controller
[INFO] [1720075166.010910]: Loading controller: speed_scaling_state_controller
[INFO] [1720075166.015029]: Controller Spawner: Loaded controllers: pos_joint_traj_controller, joint_group_vel_controller
[INFO] [1720075166.016981]: Loading controller: force_torque_sensor_controller
[INFO] [1720075166.021104]: Controller Spawner: Loaded controllers: joint_state_controller, scaled_pos_joint_traj_controller, speed_scaling_state_controller, force_torque_sensor_controller
[INFO] [1720075166.022920]: Started controllers: joint_state_controller, scaled_pos_joint_traj_controller, speed_scaling_state_controller, force_torque_sensor_controller
[ INFO] [1720075166.154356246]: Robot mode is now RUNNING
[ INFO] [1720075166.154679459]: Robot's safety mode is now NORMAL
[ INFO] [1720075180.326604372]: Robot requested program
[ INFO] [1720075180.326636985]: Sent program to robot
[ INFO] [1720075180.610013905]: Robot connected to reverse interface. Ready to receive control commands.