0
$\begingroup$

I use Universal_Robots_ROS2_Driver in order to do motion planning with MoveIt in ROS Humble. I use the Pilz Industrial Motion Planner as planning pipeline, which seems to work after some addition to the code. I can confirm that a reasonable trajectory gets generated. The utilized controller (ros2_control framework), also accepts the goal and and returns after a while the result code SUCEEDED. The catch is, the robot has not moved at all.

  • I can see the correct current joint angles of the robot in RViz, which also change when I do free-drive. So I assume the robot and the driver have connected.
  • I achieve the same behavior if I call the action provided by the conroller on console.
  • It does not matter which controller I use either scaled_joint_trajectroy_controller or joint_trajectory_controller.

How would I debug further?

EDIT

ros2_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: "$(var tf_prefix)"

io_and_status_controller:
  ros__parameters:
    tf_prefix: "$(var tf_prefix)"

force_torque_sensor_broadcaster:
  ros__parameters:
    sensor_name: $(var tf_prefix)tcp_fts_sensor
    state_interface_names:
      - force.x
      - force.y
      - force.z
      - torque.x
      - torque.y
      - torque.z
    frame_id: $(var tf_prefix)tool0
    topic_name: ft_data


joint_trajectory_controller:
  ros__parameters:
    joints:
      - $(var tf_prefix)shoulder_pan_joint
      - $(var tf_prefix)shoulder_lift_joint
      - $(var tf_prefix)elbow_joint
      - $(var tf_prefix)wrist_1_joint
      - $(var tf_prefix)wrist_2_joint
      - $(var tf_prefix)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
      $(var tf_prefix)shoulder_pan_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)shoulder_lift_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)elbow_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)wrist_1_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)wrist_2_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)wrist_3_joint: { trajectory: 0.0, goal: 0.0 }


scaled_joint_trajectory_controller:
  ros__parameters:
    joints:
      - $(var tf_prefix)shoulder_pan_joint
      - $(var tf_prefix)shoulder_lift_joint
      - $(var tf_prefix)elbow_joint
      - $(var tf_prefix)wrist_1_joint
      - $(var tf_prefix)wrist_2_joint
      - $(var tf_prefix)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
      $(var tf_prefix)shoulder_pan_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)shoulder_lift_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)elbow_joint: { trajectory: 0.0, goal: 0.}
      $(var tf_prefix)wrist_1_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)wrist_2_joint: { trajectory: 0.0, goal: 0.0 }
      $(var tf_prefix)wrist_3_joint: { trajectory: 0.0, goal: 0.0 }
    speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor

forward_velocity_controller:
  ros__parameters:
    joints:
      - $(var tf_prefix)shoulder_pan_joint
      - $(var tf_prefix)shoulder_lift_joint
      - $(var tf_prefix)elbow_joint
      - $(var tf_prefix)wrist_1_joint
      - $(var tf_prefix)wrist_2_joint
      - $(var tf_prefix)wrist_3_joint
    interface_name: velocity

forward_position_controller:
  ros__parameters:
    joints:
      - $(var tf_prefix)shoulder_pan_joint
      - $(var tf_prefix)shoulder_lift_joint
      - $(var tf_prefix)elbow_joint
      - $(var tf_prefix)wrist_1_joint
      - $(var tf_prefix)wrist_2_joint
      - $(var tf_prefix)wrist_3_joint

EDIT2:

interfaces: command interfaces

[94melbow_joint/position [available] [claimed][0m
    [96melbow_joint/velocity [available] [unclaimed][0m
    [94mgpio/io_async_success [available] [claimed][0m
    [94mgpio/standard_analog_output_cmd_0 [available] [claimed][0m
    [94mgpio/standard_analog_output_cmd_1 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_0 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_1 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_10 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_11 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_12 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_13 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_14 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_15 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_16 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_17 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_2 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_3 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_4 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_5 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_6 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_7 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_8 [available] [claimed][0m
    [94mgpio/standard_digital_output_cmd_9 [available] [claimed][0m
    [94mgpio/tool_voltage_cmd [available] [claimed][0m
    [94mhand_back_control/hand_back_control_async_success [available] [claimed][0m
    [94mhand_back_control/hand_back_control_cmd [available] [claimed][0m
    [94mpayload/cog.x [available] [claimed][0m
    [94mpayload/cog.y [available] [claimed][0m
    [94mpayload/cog.z [available] [claimed][0m
    [94mpayload/mass [available] [claimed][0m
    [94mpayload/payload_async_success [available] [claimed][0m
    [94mresend_robot_program/resend_robot_program_async_success [available] [claimed][0m
    [94mresend_robot_program/resend_robot_program_cmd [available] [claimed][0m
    [94mshoulder_lift_joint/position [available] [claimed][0m
    [96mshoulder_lift_joint/velocity [available] [unclaimed][0m
    [94mshoulder_pan_joint/position [available] [claimed][0m
    [96mshoulder_pan_joint/velocity [available] [unclaimed][0m
    [94mspeed_scaling/target_speed_fraction_async_success [available] [claimed][0m
    [94mspeed_scaling/target_speed_fraction_cmd [available] [claimed][0m
    [94mwrist_1_joint/position [available] [claimed][0m
    [96mwrist_1_joint/velocity [available] [unclaimed][0m
    [94mwrist_2_joint/position [available] [claimed][0m
    [96mwrist_2_joint/velocity [available] [unclaimed][0m
    [94mwrist_3_joint/position [available] [claimed][0m
    [96mwrist_3_joint/velocity [available] [unclaimed][0m
    [94mzero_ftsensor/zero_ftsensor_async_success [available] [claimed][0m
    [94mzero_ftsensor/zero_ftsensor_cmd [available] [claimed][0m
state interfaces
    elbow_joint/effort
    elbow_joint/position
    elbow_joint/velocity
    gpio/analog_io_type_0
    gpio/analog_io_type_1
    gpio/analog_io_type_2
    gpio/analog_io_type_3
    gpio/digital_input_0
    gpio/digital_input_1
    gpio/digital_input_10
    gpio/digital_input_11
    gpio/digital_input_12
    gpio/digital_input_13
    gpio/digital_input_14
    gpio/digital_input_15
    gpio/digital_input_16
    gpio/digital_input_17
    gpio/digital_input_2
    gpio/digital_input_3
    gpio/digital_input_4
    gpio/digital_input_5
    gpio/digital_input_6
    gpio/digital_input_7
    gpio/digital_input_8
    gpio/digital_input_9
    gpio/digital_output_0
    gpio/digital_output_1
    gpio/digital_output_10
    gpio/digital_output_11
    gpio/digital_output_12
    gpio/digital_output_13
    gpio/digital_output_14
    gpio/digital_output_15
    gpio/digital_output_16
    gpio/digital_output_17
    gpio/digital_output_2
    gpio/digital_output_3
    gpio/digital_output_4
    gpio/digital_output_5
    gpio/digital_output_6
    gpio/digital_output_7
    gpio/digital_output_8
    gpio/digital_output_9
    gpio/program_running
    gpio/robot_mode
    gpio/robot_status_bit_0
    gpio/robot_status_bit_1
    gpio/robot_status_bit_2
    gpio/robot_status_bit_3
    gpio/safety_mode
    gpio/safety_status_bit_0
    gpio/safety_status_bit_1
    gpio/safety_status_bit_10
    gpio/safety_status_bit_2
    gpio/safety_status_bit_3
    gpio/safety_status_bit_4
    gpio/safety_status_bit_5
    gpio/safety_status_bit_6
    gpio/safety_status_bit_7
    gpio/safety_status_bit_8
    gpio/safety_status_bit_9
    gpio/standard_analog_input_0
    gpio/standard_analog_input_1
    gpio/standard_analog_output_0
    gpio/standard_analog_output_1
    gpio/tool_analog_input_0
    gpio/tool_analog_input_1
    gpio/tool_analog_input_type_0
    gpio/tool_analog_input_type_1
    gpio/tool_mode
    gpio/tool_output_current
    gpio/tool_output_voltage
    gpio/tool_temperature
    shoulder_lift_joint/effort
    shoulder_lift_joint/position
    shoulder_lift_joint/velocity
    shoulder_pan_joint/effort
    shoulder_pan_joint/position
    shoulder_pan_joint/velocity
    speed_scaling/speed_scaling_factor
    system_interface/initialized
    tcp_fts_sensor/force.x
    tcp_fts_sensor/force.y
    tcp_fts_sensor/force.z
    tcp_fts_sensor/torque.x
    tcp_fts_sensor/torque.y
    tcp_fts_sensor/torque.z
    wrist_1_joint/effort
    wrist_1_joint/position
    wrist_1_joint/velocity
    wrist_2_joint/effort
    wrist_2_joint/position
wrist_2_joint/velocity
wrist_3_joint/effort
wrist_3_joint/position
wrist_3_joint/velocity

components:

Hardware Component 1
    name: ur5e
    type: system
    plugin name: ur_robot_driver/URPositionHardwareInterface
    state: id=3 label=active
    command interfaces
        shoulder_pan_joint/position [94m[available][0m [94m[claimed][0m
        shoulder_pan_joint/velocity [94m[available][0m [unclaimed]
        shoulder_lift_joint/position [94m[available][0m [94m[claimed][0m
        shoulder_lift_joint/velocity [94m[available][0m [unclaimed]
        elbow_joint/position [94m[available][0m [94m[claimed][0m
        elbow_joint/velocity [94m[available][0m [unclaimed]
        wrist_1_joint/position [94m[available][0m [94m[claimed][0m
        wrist_1_joint/velocity [94m[available][0m [unclaimed]
        wrist_2_joint/position [94m[available][0m [94m[claimed][0m
        wrist_2_joint/velocity [94m[available][0m [unclaimed]
        wrist_3_joint/position [94m[available][0m [94m[claimed][0m
        wrist_3_joint/velocity [94m[available][0m [unclaimed]
        gpio/io_async_success [94m[available][0m [94m[claimed][0m
        speed_scaling/target_speed_fraction_cmd [94m[available][0m [94m[claimed][0m
        speed_scaling/target_speed_fraction_async_success [94m[available][0m [94m[claimed][0m
        resend_robot_program/resend_robot_program_cmd [94m[available][0m [94m[claimed][0m
        resend_robot_program/resend_robot_program_async_success [94m[available][0m [94m[claimed][0m
        hand_back_control/hand_back_control_cmd [94m[available][0m [94m[claimed][0m
        hand_back_control/hand_back_control_async_success [94m[available][0m [94m[claimed][0m
        payload/mass [94m[available][0m [94m[claimed][0m
        payload/cog.x [94m[available][0m [94m[claimed][0m
        payload/cog.y [94m[available][0m [94m[claimed][0m
        payload/cog.z [94m[available][0m [94m[claimed][0m
        payload/payload_async_success [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_0 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_1 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_2 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_3 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_4 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_5 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_6 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_7 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_8 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_9 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_10 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_11 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_12 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_13 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_14 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_15 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_16 [94m[available][0m [94m[claimed][0m
        gpio/standard_digital_output_cmd_17 [94m[available][0m [94m[claimed][0m
        gpio/standard_analog_output_cmd_0 [94m[available][0m [94m[claimed][0m
        gpio/standard_analog_output_cmd_1 [94m[available][0m [94m[claimed][0m
        gpio/tool_voltage_cmd [94m[available][0m [94m[claimed][0m
        zero_ftsensor/zero_ftsensor_cmd [94m[available][0m [94m[claimed][0m
        zero_ftsensor/zero_ftsensor_async_success [94m[available][0m [94m[claimed][0m
    state interfaces
        shoulder_pan_joint/position [94m[available][0m
        shoulder_pan_joint/velocity [94m[available][0m
        shoulder_pan_joint/effort [94m[available][0m
        shoulder_lift_joint/position [94m[available][0m
        shoulder_lift_joint/velocity [94m[available][0m
        shoulder_lift_joint/effort [94m[available][0m
        elbow_joint/position [94m[available][0m
        elbow_joint/velocity [94m[available][0m
        elbow_joint/effort [94m[available][0m
        wrist_1_joint/position [94m[available][0m
        wrist_1_joint/velocity [94m[available][0m
        wrist_1_joint/effort [94m[available][0m
        wrist_2_joint/position [94m[available][0m
        wrist_2_joint/velocity [94m[available][0m
        wrist_2_joint/effort [94m[available][0m
        wrist_3_joint/position [94m[available][0m
        wrist_3_joint/velocity [94m[available][0m
        wrist_3_joint/effort [94m[available][0m
        speed_scaling/speed_scaling_factor [94m[available][0m
        tcp_fts_sensor/force.x [94m[available][0m
        tcp_fts_sensor/force.y [94m[available][0m
        tcp_fts_sensor/force.z [94m[available][0m
        tcp_fts_sensor/torque.x [94m[available][0m
        tcp_fts_sensor/torque.y [94m[available][0m
        tcp_fts_sensor/torque.z [94m[available][0m
        gpio/digital_output_0 [94m[available][0m
        gpio/digital_input_0 [94m[available][0m
        gpio/digital_output_1 [94m[available][0m
        gpio/digital_input_1 [94m[available][0m
        gpio/digital_output_2 [94m[available][0m
        gpio/digital_input_2 [94m[available][0m
        gpio/digital_output_3 [94m[available][0m
        gpio/digital_input_3 [94m[available][0m
        gpio/digital_output_4 [94m[available][0m
        gpio/digital_input_4 [94m[available][0m
        gpio/digital_output_5 [94m[available][0m
        gpio/digital_input_5 [94m[available][0m
        gpio/digital_output_6 [94m[available][0m
        gpio/digital_input_6 [94m[available][0m
        gpio/digital_output_7 [94m[available][0m
        gpio/digital_input_7 [94m[available][0m
        gpio/digital_output_8 [94m[available][0m
        gpio/digital_input_8 [94m[available][0m
        gpio/digital_output_9 [94m[available][0m
        gpio/digital_input_9 [94m[available][0m
        gpio/digital_output_10 [94m[available][0m
        gpio/digital_input_10 [94m[available][0m
        gpio/digital_output_11 [94m[available][0m
        gpio/digital_input_11 [94m[available][0m
        gpio/digital_output_12 [94m[available][0m
        gpio/digital_input_12 [94m[available][0m
        gpio/digital_output_13 [94m[available][0m
        gpio/digital_input_13 [94m[available][0m
        gpio/digital_output_14 [94m[available][0m
        gpio/digital_input_14 [94m[available][0m
        gpio/digital_output_15 [94m[available][0m
        gpio/digital_input_15 [94m[available][0m
        gpio/digital_output_16 [94m[available][0m
        gpio/digital_input_16 [94m[available][0m
        gpio/digital_output_17 [94m[available][0m
        gpio/digital_input_17 [94m[available][0m
        gpio/safety_status_bit_0 [94m[available][0m
        gpio/safety_status_bit_1 [94m[available][0m
        gpio/safety_status_bit_2 [94m[available][0m
        gpio/safety_status_bit_3 [94m[available][0m
        gpio/safety_status_bit_4 [94m[available][0m
        gpio/safety_status_bit_5 [94m[available][0m
        gpio/safety_status_bit_6 [94m[available][0m
        gpio/safety_status_bit_7 [94m[available][0m
        gpio/safety_status_bit_8 [94m[available][0m
        gpio/safety_status_bit_9 [94m[available][0m
        gpio/safety_status_bit_10 [94m[available][0m
        gpio/analog_io_type_0 [94m[available][0m
        gpio/robot_status_bit_0 [94m[available][0m
        gpio/analog_io_type_1 [94m[available][0m
        gpio/robot_status_bit_1 [94m[available][0m
        gpio/analog_io_type_2 [94m[available][0m
        gpio/robot_status_bit_2 [94m[available][0m
        gpio/analog_io_type_3 [94m[available][0m
        gpio/robot_status_bit_3 [94m[available][0m
        gpio/tool_analog_input_type_0 [94m[available][0m
        gpio/tool_analog_input_0 [94m[available][0m
        gpio/standard_analog_input_0 [94m[available][0m
        gpio/standard_analog_output_0 [94m[available][0m
        gpio/tool_analog_input_type_1 [94m[available][0m
        gpio/tool_analog_input_1 [94m[available][0m
        gpio/standard_analog_input_1 [94m[available][0m
        gpio/standard_analog_output_1 [94m[available][0m
        gpio/tool_output_voltage [94m[available][0m
        gpio/robot_mode [94m[available][0m
        gpio/safety_mode [94m[available][0m
        gpio/tool_mode [94m[available][0m
        gpio/tool_output_current [94m[available][0m
        gpio/tool_temperature [94m[available][0m
        system_interface/initialized [94m[available][0m
        gpio/program_running [94m[available][0m
$\endgroup$
3
  • $\begingroup$ could you share your joint_trajectory_controller config? it should not succeed if the tolerances are not met, but this depends on your configuration.. $\endgroup$ Feb 12 at 13:17
  • $\begingroup$ Since the default tolerances are 0.2 for the trajectory and 0.1 for the goal, the initial case was indeed, that the state is outside the tolerances. However I set the tolerances for both, trajectory and goal, to zero. That should disable them, correct? Edit: I did enable show_errors in check_state_tolerance_per_joint in order to find that error. But it didn't appear after disabling. $\endgroup$
    – NotARobot
    Feb 12 at 13:50
  • $\begingroup$ Atm, I try to trace how the controllers get and set the joints in detail. I can't comprehend, why there is no error reported, regarding "Not being able to set resource to X" or something like that. $\endgroup$
    – NotARobot
    Feb 12 at 14:04

2 Answers 2

0
$\begingroup$

You disabled the goal+state tolerances. try to set nonzero values, just to confirm that JTC would recognize the tolerance error

  goal_time: 0.0
  $(var tf_prefix)shoulder_pan_joint: { trajectory: 0.0, goal: 0.0 }
  $(var tf_prefix)shoulder_lift_joint: { trajectory: 0.0, goal: 0.0 }
  $(var tf_prefix)elbow_joint: { trajectory: 0.0, goal: 0.0 }
  $(var tf_prefix)wrist_1_joint: { trajectory: 0.0, goal: 0.0 }
  $(var tf_prefix)wrist_2_joint: { trajectory: 0.0, goal: 0.0 }
  $(var tf_prefix)wrist_3_joint: { trajectory: 0.0, goal: 0.0 }

What does the ros2controlcli tell you? ros2 control list_hardware_interfaces, ros2 control list_hardware_components -v

$\endgroup$
5
  • $\begingroup$ I set the tolerances to 99.0, and can confirm that they are set properly $\endgroup$
    – NotARobot
    Feb 12 at 15:00
  • $\begingroup$ Can you confirm that JTC aborts now? Or what do you mean by "set properly"? And what about the ros2controlcli? $\endgroup$ Feb 12 at 21:01
  • $\begingroup$ JTC doesn't abort now, since I've set the tolerances to 99.0, which is relatively big in regard to the default value of 0.2. I've added print out commands in tolerances.hpp basically printing out all tolerances in function check_state_tolerance_per_joint. JTC aborts however if I set the tolerance to 0.2 for the state, which originally brought me to look at the function. The original planning was of by 0.002 or something small like that. The output from ros2 control was added at the end of my question. Do you require other output? Have I missed something? $\endgroup$
    – NotARobot
    Feb 13 at 7:53
  • $\begingroup$ I was just asking about the tolerances, because you set them 0 (which means deactivated) in your first question above. If you set them to something reasonable, it should abort and not return SUCCEED. $\endgroup$ Feb 13 at 8:18
  • $\begingroup$ the output seems to be fine, all you command-joints are claimed with position interface. If you already compile your stack from source, I'd suggest to introspect the values inside your hardware component. It seems that there is something wrong with the communication with your robot. E.g., you can use datatamer as suggested in this PR $\endgroup$ Feb 13 at 8:22
0
$\begingroup$

@Christoph Froehlich was right, the issue were communication problems with the UR.

You will receive robot state information from the driver even if you can't control the robot. My issue was that I used the default value of reverse_ip which is 0.0.0.0, this is also the value default in the ur_drivers urX.launch.py. However, the URPositionHardwareInterface::on_activate will invalidate 0.0.0.0 and set it to an empty string. This in turn triggers the underlying Universal Robots Client Library to use 172.18.0.2 as default IP.

On the control panel of the UR in the protocol:

Not able to open socket script_command_socket to host: 172.18.0.2 at port: 50004: Connection timed out

I am glad that that resolved itself, but I don't understand why there is no feedback to the controller, that the hardware interface didn't succeed with the given control. Furthermore, I can't understand why the reverse_ip parameter is not a default-less required parameter in the ur_driver.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.