|
62 | 62 | kinematics_parameters_file |
63 | 63 | physical_parameters_file |
64 | 64 | visual_parameters_file |
| 65 | + generate_ros2_control_tag:=true |
65 | 66 | transmission_hw_interface:=hardware_interface/PositionJointInterface |
66 | 67 | safety_limits:=false |
67 | 68 | safety_pos_margin:=0.15 |
|
104 | 105 | force_abs_paths="${sim_gazebo or sim_ignition}"/> |
105 | 106 |
|
106 | 107 |
|
107 | | - <!-- ros2 control include --> |
108 | | - <xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" /> |
109 | | - <!-- ros2 control instance --> |
110 | | - <xacro:ur_ros2_control |
111 | | - name="${name}" |
112 | | - use_fake_hardware="${use_fake_hardware}" |
113 | | - initial_positions="${initial_positions}" |
114 | | - fake_sensor_commands="${fake_sensor_commands}" |
115 | | - headless_mode="${headless_mode}" |
116 | | - sim_gazebo="${sim_gazebo}" |
117 | | - sim_ignition="${sim_ignition}" |
118 | | - script_filename="${script_filename}" |
119 | | - output_recipe_filename="${output_recipe_filename}" |
120 | | - input_recipe_filename="${input_recipe_filename}" |
121 | | - tf_prefix="${tf_prefix}" |
122 | | - hash_kinematics="${kinematics_hash}" |
123 | | - robot_ip="${robot_ip}" |
124 | | - use_tool_communication="${use_tool_communication}" |
125 | | - tool_voltage="${tool_voltage}" |
126 | | - tool_parity="${tool_parity}" |
127 | | - tool_baud_rate="${tool_baud_rate}" |
128 | | - tool_stop_bits="${tool_stop_bits}" |
129 | | - tool_rx_idle_chars="${tool_rx_idle_chars}" |
130 | | - tool_tx_idle_chars="${tool_tx_idle_chars}" |
131 | | - tool_device_name="${tool_device_name}" |
132 | | - tool_tcp_port="${tool_tcp_port}" |
133 | | - reverse_port="${reverse_port}" |
134 | | - script_sender_port="${script_sender_port}" |
135 | | - reverse_ip="${reverse_ip}" |
136 | | - script_command_port="${script_command_port}" |
137 | | - trajectory_port="${trajectory_port}" |
138 | | - non_blocking_read="${non_blocking_read}" |
139 | | - keep_alive_count="${keep_alive_count}" |
140 | | - /> |
| 108 | + <xacro:if value="${generate_ros2_control_tag}"> |
| 109 | + <!-- ros2 control include --> |
| 110 | + <xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" /> |
| 111 | + <!-- ros2 control instance --> |
| 112 | + <xacro:ur_ros2_control |
| 113 | + name="${name}" |
| 114 | + use_fake_hardware="${use_fake_hardware}" |
| 115 | + initial_positions="${initial_positions}" |
| 116 | + fake_sensor_commands="${fake_sensor_commands}" |
| 117 | + headless_mode="${headless_mode}" |
| 118 | + sim_gazebo="${sim_gazebo}" |
| 119 | + sim_ignition="${sim_ignition}" |
| 120 | + script_filename="${script_filename}" |
| 121 | + output_recipe_filename="${output_recipe_filename}" |
| 122 | + input_recipe_filename="${input_recipe_filename}" |
| 123 | + tf_prefix="${tf_prefix}" |
| 124 | + hash_kinematics="${kinematics_hash}" |
| 125 | + robot_ip="${robot_ip}" |
| 126 | + use_tool_communication="${use_tool_communication}" |
| 127 | + tool_voltage="${tool_voltage}" |
| 128 | + tool_parity="${tool_parity}" |
| 129 | + tool_baud_rate="${tool_baud_rate}" |
| 130 | + tool_stop_bits="${tool_stop_bits}" |
| 131 | + tool_rx_idle_chars="${tool_rx_idle_chars}" |
| 132 | + tool_tx_idle_chars="${tool_tx_idle_chars}" |
| 133 | + tool_device_name="${tool_device_name}" |
| 134 | + tool_tcp_port="${tool_tcp_port}" |
| 135 | + reverse_port="${reverse_port}" |
| 136 | + script_sender_port="${script_sender_port}" |
| 137 | + reverse_ip="${reverse_ip}" |
| 138 | + script_command_port="${script_command_port}" |
| 139 | + trajectory_port="${trajectory_port}" |
| 140 | + non_blocking_read="${non_blocking_read}" |
| 141 | + keep_alive_count="${keep_alive_count}" |
| 142 | + /> |
| 143 | + </xacro:if> |
141 | 144 |
|
142 | 145 | <!-- Add URDF transmission elements (for ros_control) --> |
143 | 146 | <!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />--> |
|
0 commit comments