|
35 | 35 | kinematics_parameters_file="$(find chonkur_description)/config/calibrated_kinematics.yaml" |
36 | 36 | physical_parameters_file="$(find ur_description)/config/ur10e/physical_parameters.yaml" |
37 | 37 | visual_parameters_file="$(find ur_description)/config/ur10e/visual_parameters.yaml" |
38 | | - transmission_hw_interface="hardware_interface/PositionJointInterface" |
39 | 38 | safety_limits="false" |
40 | 39 | safety_pos_margin="0.15" |
41 | 40 | safety_k_position="20" |
42 | | - use_fake_hardware="${use_fake_hardware}" |
43 | | - fake_sensor_commands="false" |
44 | | - sim_gazebo="${sim_gazebo}" |
45 | | - sim_ignition="${sim_ignition}" |
46 | | - generate_ros2_control_tag="${generate_ros2_control_tag}" |
47 | | - headless_mode="${headless_mode}" |
48 | | - initial_positions="${xacro.load_yaml(initial_positions_file)}" |
49 | | - use_tool_communication="false" |
50 | | - tool_voltage="0" |
51 | | - tool_parity="0" |
52 | | - tool_baud_rate="115200" |
53 | | - tool_stop_bits="1" |
54 | | - tool_rx_idle_chars="1.5" |
55 | | - tool_tx_idle_chars="3.5" |
56 | | - tool_device_name="/tmp/ttyUR" |
57 | | - tool_tcp_port="54321" |
58 | | - robot_ip="${chonkur_ip}" |
59 | | - script_filename="$(find ur_client_library)/resources/external_control.urscript" |
60 | | - output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt" |
61 | | - input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt" |
62 | | - reverse_ip="0.0.0.0" |
63 | | - script_command_port="50004" |
64 | 41 | > |
65 | 42 | <origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world --> |
66 | 43 | </xacro:ur_robot> |
67 | 44 |
|
| 45 | + <xacro:if value="${generate_ros2_control_tag}"> |
| 46 | + <xacro:include filename="$(find ur_robot_driver)/urdf/ur.ros2_control.xacro" /> |
| 47 | + <xacro:include filename="$(find ur_description)/urdf/inc/ur_transmissions.xacro" /> |
| 48 | + <xacro:ur_ros2_control |
| 49 | + name="${ros2_control_name}" |
| 50 | + tf_prefix="${tf_prefix}" |
| 51 | + kinematics_parameters_file="$(find chonkur_description)/config/calibrated_kinematics.yaml" |
| 52 | + transmission_hw_interface="hardware_interface/PositionJointInterface" |
| 53 | + use_mock_hardware="$(arg use_fake_hardware)" |
| 54 | + mock_sensor_commands="$(arg use_fake_hardware)" |
| 55 | + headless_mode="${headless_mode}" |
| 56 | + initial_positions="${xacro.load_yaml(initial_positions_file)}" |
| 57 | + use_tool_communication="false" |
| 58 | + tool_voltage="0" |
| 59 | + tool_parity="0" |
| 60 | + tool_baud_rate="115200" |
| 61 | + tool_stop_bits="1" |
| 62 | + tool_rx_idle_chars="1.5" |
| 63 | + tool_tx_idle_chars="3.5" |
| 64 | + tool_device_name="/tmp/ttyUR" |
| 65 | + tool_tcp_port="54321" |
| 66 | + robot_ip="${chonkur_ip}" |
| 67 | + script_filename="$(find ur_client_library)/resources/external_control.urscript" |
| 68 | + output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt" |
| 69 | + input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt" |
| 70 | + reverse_ip="0.0.0.0" |
| 71 | + script_command_port="50004" |
| 72 | + reverse_port="50001" |
| 73 | + script_sender_port="50002" |
| 74 | + trajectory_port="50003" |
| 75 | + /> |
| 76 | + </xacro:if> |
| 77 | + |
68 | 78 | <xacro:if value="${sim_gazebo}"> |
69 | 79 | <!-- Gazebo plugins --> |
70 | 80 | <gazebo reference="world"> |
|
88 | 98 | </gazebo> |
89 | 99 | </xacro:if> |
90 | 100 |
|
| 101 | + |
| 102 | + |
91 | 103 | <!-- END EFFECTOR STACK --> |
92 | 104 |
|
93 | 105 | <xacro:include filename="$(find chonkur_description)/urdf/endeff_stack_macro.xacro"/> |
|
0 commit comments