Skip to content

Commit

Permalink
Merge pull request #520 from gavanderhoorn/fix_yaml_loading
Browse files Browse the repository at this point in the history
Load yaml files in read_model_data(..), nowhere else
  • Loading branch information
gavanderhoorn authored Jun 30, 2020
2 parents 20034f6 + 715f9e2 commit 92cf300
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 14 deletions.
19 changes: 13 additions & 6 deletions ur_description/urdf/inc/ur_common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,19 @@
and as such should be considered to be for internal use only.
-->
<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file">
<xacro:property name="__limits" value="${joint_limits_parameters_file['joint_limits']}"/>
<xacro:property name="__dh_parameters" value="${physical_parameters_file['dh_parameters']}"/>
<xacro:property name="__offsets" value="${physical_parameters_file['offsets']}"/>
<xacro:property name="__inertia_parameters" value="${physical_parameters_file['inertia_parameters']}" />
<xacro:property name="__mesh_files" value="${visual_parameters_file['mesh_files']}" />
<xacro:property name="__kinematics" value="${kinematics_parameters_file['kinematics']}" />
<!-- Read .yaml files from disk, load content into properties -->
<xacro:property name="__joint_limit_parameters" value="${load_yaml(joint_limits_parameters_file)}"/>
<xacro:property name="__kinematics_parameters" value="${load_yaml(kinematics_parameters_file)}"/>
<xacro:property name="__physical_parameters" value="${load_yaml(physical_parameters_file)}"/>
<xacro:property name="__visual_parameters" value="${load_yaml(visual_parameters_file)}"/>

<!-- Extract subsections from yaml dictionaries -->
<xacro:property name="__limits" value="${__joint_limit_parameters['joint_limits']}"/>
<xacro:property name="__dh_parameters" value="${__physical_parameters['dh_parameters']}"/>
<xacro:property name="__offsets" value="${__physical_parameters['offsets']}"/>
<xacro:property name="__inertia_parameters" value="${__physical_parameters['inertia_parameters']}" />
<xacro:property name="__mesh_files" value="${__visual_parameters['mesh_files']}" />
<xacro:property name="__kinematics" value="${__kinematics_parameters['kinematics']}" />

<!-- JOINTS LIMIT PARAMETERS -->
<xacro:property name="shoulder_pan_lower_limit" value="${__limits['shoulder_pan']['min_position']}" scope="parent"/>
Expand Down
8 changes: 4 additions & 4 deletions ur_description/urdf/ur.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@
<!-- arm -->
<xacro:ur_robot
prefix=""
joint_limits_parameters_file="${load_yaml('$(arg joint_limit_params)')}"
kinematics_parameters_file="${load_yaml('$(arg kinematics_params)')}"
physical_parameters_file="${load_yaml('$(arg physical_params)')}"
visual_parameters_file="${load_yaml('$(arg visual_params)')}"
joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(arg visual_params)"
transmission_hw_interface="$(arg transmission_hw_interface)"
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
Expand Down
8 changes: 4 additions & 4 deletions ur_gazebo/urdf/ur_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@
<xacro:include filename="$(find ur_gazebo)/urdf/common.gazebo.xacro"/>

<!-- arm -->
<xacro:ur_gazebo_robot prefix="" joint_limits_parameters_file="${load_yaml('$(arg joint_limit_params)')}"
kinematics_parameters_file="${load_yaml('$(arg kinematics_params)')}"
physical_parameters_file="${load_yaml('$(arg physical_params)')}"
visual_parameters_file="${load_yaml('$(arg visual_params)')}"
<xacro:ur_gazebo_robot prefix="" joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(arg visual_params)"
transmission_hw_interface="$(arg transmission_hw_interface)"
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
Expand Down

0 comments on commit 92cf300

Please sign in to comment.