Skip to content

Commit beef717

Browse files
changed xacro:arg name for kinematics_params, physical_params and visual_params to make it match the arguments handed over by ur_control.launch.py // otherwise default values were used
1 parent 98f8579 commit beef717

File tree

1 file changed

+8
-6
lines changed

1 file changed

+8
-6
lines changed

my_robot_cell/my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,9 @@
1111
<!--You could aswell point to ur_description but this way you make sure you use the same files as start_robot.launch.py which searches in runtime_config_package for joint_limits.yaml, physical_parameters.yaml, visual_parameters.yaml and in description_package for default_kinematics.yaml (last one can be overwritten)-->
1212
<xacro:arg name="ur_type" default="ur20"/>
1313
<xacro:arg name="joint_limit_params" default="$(find my_robot_cell_control)/config/$(arg ur_type)/joint_limits.yaml"/>
14-
<xacro:arg name="kinematics_params_file" default="$(find my_robot_cell_control)/config/$(arg ur_type)/default_kinematics.yaml"/>
15-
<xacro:arg name="physical_parameters_file" default="$(find my_robot_cell_control)/config/$(arg ur_type)/physical_parameters.yaml"/>
16-
<xacro:arg name="visual_parameters_file" default="$(find my_robot_cell_control)/config/$(arg ur_type)/visual_parameters.yaml"/>
14+
<xacro:arg name="kinematics_params" default="$(find my_robot_cell_control)/config/$(arg ur_type)/default_kinematics.yaml"/>
15+
<xacro:arg name="physical_params" default="$(find my_robot_cell_control)/config/$(arg ur_type)/physical_parameters.yaml"/>
16+
<xacro:arg name="visual_params" default="$(find my_robot_cell_control)/config/$(arg ur_type)/visual_parameters.yaml"/>
1717

1818
<xacro:arg name="robot_ip" default="0.0.0.0"/>
1919
<xacro:arg name="headless_mode" default="false" />
@@ -25,20 +25,22 @@
2525
<!--find hash_kinematics in calibration yaml-->
2626
<xacro:arg name="hash_kinematics" default="calib_4890363623803256388" />
2727

28+
2829
<link name="world" />
2930

3031
<!--Create the scene description including the robot-->
3132
<xacro:my_robot_cell
3233
parent="world"
3334
ur_type="$(arg ur_type)"
3435
joint_limits_parameters_file="$(arg joint_limit_params)"
35-
kinematics_parameters_file="$(arg kinematics_params_file)"
36-
physical_parameters_file="$(arg physical_parameters_file)"
37-
visual_parameters_file="$(arg visual_parameters_file)"
36+
kinematics_parameters_file="$(arg kinematics_params)"
37+
physical_parameters_file="$(arg physical_params)"
38+
visual_parameters_file="$(arg visual_params)"
3839
>
3940
<origin xyz="0 0 1" rpy="0 0 0" />
4041
</xacro:my_robot_cell>
4142

43+
4244
<!--Create the control tag for the UR robot-->
4345
<xacro:ur_ros2_control
4446
name="$(arg ur_type)"

0 commit comments

Comments
 (0)