Skip to content
Closed
Show file tree
Hide file tree
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
11 changes: 10 additions & 1 deletion ur_description/urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,11 @@
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<xacro:arg name="robot_ip" default="0.0.0.0" />
<xacro:arg name="script_filename" default="$(find ur_robot_driver)/resources/ros_control.urscript"/>
<xacro:arg name="output_recipe_filename" default="$(find ur_robot_driver)/resources/rtde_input_recipe.txt"/>
<xacro:arg name="input_recipe_filename" default="$(find ur_robot_driver)/resources/rtde_input_recipe.txt"/>

<!-- arm -->
<xacro:ur_robot
prefix="$(arg prefix)"
Expand All @@ -36,5 +41,9 @@
safety_k_position="$(arg safety_k_position)"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"
initial_positions="${load_yaml(initial_positions_file)}" />
initial_positions="${load_yaml(initial_positions_file)}"
robot_ip="$(arg robot_ip)"
script_filename="$(arg script_filename)"
output_recipe_filename="$(arg output_recipe_filename)"
input_recipe_filename="$(arg input_recipe_filename)" />
</robot>
23 changes: 10 additions & 13 deletions ur_description/urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,10 @@
safety_k_position:=20
use_fake_hardware:=false
fake_sensor_commands:=false
robot_ip:=0.0.0.0
script_filename:=to_be_filled_by_ur_robot_driver
output_recipe_filename:=to_be_filled_by_ur_robot_driver
input_recipe_filename:=to_be_filled_by_ur_robot_driver
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}">
<!-- Load configuration data from the provided .yaml files -->
<xacro:read_model_data
Expand All @@ -73,27 +77,20 @@
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"/>

<!-- Data files required by the UR driver -->
<xacro:arg name="script_filename" default="$(find ur_robot_driver)/resources/ros_control.urscript"/>
<xacro:arg name="output_recipe_filename" default="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"/>
<xacro:arg name="input_recipe_filename" default="$(find ur_robot_driver)/resources/rtde_input_recipe.txt"/>
<xacro:arg name="robot_ip" default="10.0.1.186"/>


<!-- ros2 control include -->
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="URPositionHardwareInterface" prefix="${prefix}"
use_fake_hardware="$(arg use_fake_hardware)"
use_fake_hardware="${use_fake_hardware}"
initial_positions="${initial_positions}"
fake_sensor_commands="$(arg fake_sensor_commands)"
script_filename="$(arg script_filename)"
output_recipe_filename="$(arg output_recipe_filename)"
input_recipe_filename="$(arg input_recipe_filename)"
fake_sensor_commands="${fake_sensor_commands}"
script_filename="${script_filename}"
output_recipe_filename="${output_recipe_filename}"
input_recipe_filename="${input_recipe_filename}"
tf_prefix=""
hash_kinematics="${kinematics_hash}"
robot_ip="$(arg robot_ip)" />
robot_ip="${robot_ip}" />

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