Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
71 changes: 37 additions & 34 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@
kinematics_parameters_file
physical_parameters_file
visual_parameters_file
generate_ros2_control_tag:=true
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
Expand Down Expand Up @@ -104,40 +105,42 @@
force_abs_paths="${sim_gazebo or sim_ignition}"/>


<!-- ros2 control include -->
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="${name}"
use_fake_hardware="${use_fake_hardware}"
initial_positions="${initial_positions}"
fake_sensor_commands="${fake_sensor_commands}"
headless_mode="${headless_mode}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
script_filename="${script_filename}"
output_recipe_filename="${output_recipe_filename}"
input_recipe_filename="${input_recipe_filename}"
tf_prefix="${tf_prefix}"
hash_kinematics="${kinematics_hash}"
robot_ip="${robot_ip}"
use_tool_communication="${use_tool_communication}"
tool_voltage="${tool_voltage}"
tool_parity="${tool_parity}"
tool_baud_rate="${tool_baud_rate}"
tool_stop_bits="${tool_stop_bits}"
tool_rx_idle_chars="${tool_rx_idle_chars}"
tool_tx_idle_chars="${tool_tx_idle_chars}"
tool_device_name="${tool_device_name}"
tool_tcp_port="${tool_tcp_port}"
reverse_port="${reverse_port}"
script_sender_port="${script_sender_port}"
reverse_ip="${reverse_ip}"
script_command_port="${script_command_port}"
trajectory_port="${trajectory_port}"
non_blocking_read="${non_blocking_read}"
keep_alive_count="${keep_alive_count}"
/>
<xacro:if value="${generate_ros2_control_tag}">
<!-- ros2 control include -->
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="${name}"
use_fake_hardware="${use_fake_hardware}"
initial_positions="${initial_positions}"
fake_sensor_commands="${fake_sensor_commands}"
headless_mode="${headless_mode}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
script_filename="${script_filename}"
output_recipe_filename="${output_recipe_filename}"
input_recipe_filename="${input_recipe_filename}"
tf_prefix="${tf_prefix}"
hash_kinematics="${kinematics_hash}"
robot_ip="${robot_ip}"
use_tool_communication="${use_tool_communication}"
tool_voltage="${tool_voltage}"
tool_parity="${tool_parity}"
tool_baud_rate="${tool_baud_rate}"
tool_stop_bits="${tool_stop_bits}"
tool_rx_idle_chars="${tool_rx_idle_chars}"
tool_tx_idle_chars="${tool_tx_idle_chars}"
tool_device_name="${tool_device_name}"
tool_tcp_port="${tool_tcp_port}"
reverse_port="${reverse_port}"
script_sender_port="${script_sender_port}"
reverse_ip="${reverse_ip}"
script_command_port="${script_command_port}"
trajectory_port="${trajectory_port}"
non_blocking_read="${non_blocking_read}"
keep_alive_count="${keep_alive_count}"
/>
</xacro:if>

<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
Expand Down