Skip to content

Generically expose URDF joint dynamics. #56

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 16 commits into
base: rolling
Choose a base branch
from
Open
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
19 changes: 19 additions & 0 deletions config/joint_dynamics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
joint_dynamics:
shoulder_pan_joint:
damping: 0.0
friction: 0.0
shoulder_lift_joint:
damping: 0.0
friction: 0.0
elbow_joint:
damping: 0.0
friction: 0.0
wrist_1_joint:
damping: 0.0
friction: 0.0
wrist_2_joint:
damping: 0.0
friction: 0.0
wrist_3_joint:
damping: 0.0
friction: 0.0
19 changes: 19 additions & 0 deletions test/test_joint_dynamics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
joint_dynamics:
shoulder_pan_joint:
damping: 0.123
friction: 1.234
shoulder_lift_joint:
damping: 0.234
friction: 2.345
elbow_joint:
damping: 0.345
friction: 3.456
wrist_1_joint:
damping: 0.456
friction: 4.567
wrist_2_joint:
damping: 0.567
friction: 5.678
wrist_3_joint:
damping: 0.678
friction: 6.789
19 changes: 18 additions & 1 deletion urdf/inc/ur_common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -41,14 +41,15 @@
<mesh filename="${mesh}"/>
</xacro:macro>

<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file force_abs_paths">
<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file joint_dynamics force_abs_paths">
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think I would prefer passing the filename down to here as we do with the other parameters, as well.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, I am not sure. It would be nicer to keep it on one level, however this way it is backwards compatible.


<xacro:property name="force_abs_paths" value="${force_abs_paths}" scope="parent"/>
<!-- Read .yaml files from disk, load content into properties -->
<xacro:property name="config_joint_limit_parameters" value="${xacro.load_yaml(joint_limits_parameters_file)}"/>
<xacro:property name="config_kinematics_parameters" value="${xacro.load_yaml(kinematics_parameters_file)}"/>
<xacro:property name="config_physical_parameters" value="${xacro.load_yaml(physical_parameters_file)}"/>
<xacro:property name="config_visual_parameters" value="${xacro.load_yaml(visual_parameters_file)}"/>
<xacro:property name="config_joint_dynamics" value="${joint_dynamics}" scope="parent"/>

<!-- Extract subsections from yaml dictionaries -->
<xacro:property name="sec_limits" value="${config_joint_limit_parameters['joint_limits']}"/>
Expand All @@ -57,6 +58,7 @@
<xacro:property name="sec_inertia_parameters" value="${config_physical_parameters['inertia_parameters']}" />
<xacro:property name="sec_mesh_files" value="${config_visual_parameters['mesh_files']}" scope="parent"/>
<xacro:property name="sec_kinematics" value="${config_kinematics_parameters['kinematics']}" />
<xacro:property name="sec_joint_dynamics" value="${config_joint_dynamics['joint_dynamics']}" scope="parent"/>

<!-- JOINTS LIMIT PARAMETERS -->
<xacro:property name="shoulder_pan_lower_limit" value="${sec_limits['shoulder_pan_joint']['min_position']}" scope="parent"/>
Expand Down Expand Up @@ -84,6 +86,21 @@
<xacro:property name="wrist_3_velocity_limit" value="${sec_limits['wrist_3_joint']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_3_effort_limit" value="${sec_limits['wrist_3_joint']['max_effort']}" scope="parent"/>


<!-- JOINT DYNAMICS PARAMETERS -->
<xacro:property name="shoulder_pan_damping" value="${sec_joint_dynamics['shoulder_pan_joint']['damping']}" scope="parent"/>
<xacro:property name="shoulder_pan_friction" value="${sec_joint_dynamics['shoulder_pan_joint']['friction']}" scope="parent"/>
<xacro:property name="shoulder_lift_damping" value="${sec_joint_dynamics['shoulder_lift_joint']['damping']}" scope="parent"/>
<xacro:property name="shoulder_lift_friction" value="${sec_joint_dynamics['shoulder_lift_joint']['friction']}" scope="parent"/>
<xacro:property name="elbow_joint_damping" value="${sec_joint_dynamics['elbow_joint']['damping']}" scope="parent"/>
<xacro:property name="elbow_joint_friction" value="${sec_joint_dynamics['elbow_joint']['friction']}" scope="parent"/>
<xacro:property name="wrist_1_damping" value="${sec_joint_dynamics['wrist_1_joint']['damping']}" scope="parent"/>
<xacro:property name="wrist_1_friction" value="${sec_joint_dynamics['wrist_1_joint']['friction']}" scope="parent"/>
<xacro:property name="wrist_2_damping" value="${sec_joint_dynamics['wrist_2_joint']['damping']}" scope="parent"/>
<xacro:property name="wrist_2_friction" value="${sec_joint_dynamics['wrist_2_joint']['friction']}" scope="parent"/>
<xacro:property name="wrist_3_damping" value="${sec_joint_dynamics['wrist_3_joint']['damping']}" scope="parent"/>
<xacro:property name="wrist_3_friction" value="${sec_joint_dynamics['wrist_3_joint']['friction']}" scope="parent"/>

<!-- DH PARAMETERS -->
<xacro:property name="d1" value="${sec_dh_parameters['d1']}" scope="parent"/>
<xacro:property name="a2" value="${sec_dh_parameters['a2']}" scope="parent"/>
Expand Down
6 changes: 6 additions & 0 deletions urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,11 @@
<!--When using gazebo simulations absolute paths are necessary.-->
<xacro:arg name="force_abs_paths" default="false" />

<!-- Default joint dynamics has friction and damping equal to 0, but useful to specialize for simulations -->
<xacro:arg name="joint_dynamics_file" default="$(find ur_description)/config/joint_dynamics.yaml"/>

<xacro:property name="joint_dynamics_file" default="$(arg joint_dynamics_file)"/>

<!-- create link fixed to the "world" -->
<link name="world" />

Expand All @@ -38,6 +43,7 @@
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
safety_k_position="$(arg safety_k_position)"
joint_dynamics="${xacro.load_yaml(joint_dynamics_file)}"
force_abs_paths="$(arg force_abs_paths)"
>
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
Expand Down
14 changes: 8 additions & 6 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20
joint_dynamics:=${dict(joint_dynamics=dict(shoulder_pan_joint=dict(damping=0.0, friction=0.0), shoulder_lift_joint=dict(damping=0.0, friction=0.0), elbow_joint=dict(damping=0.0, friction=0.0), wrist_1_joint=dict(damping=0.0, friction=0.0), wrist_2_joint=dict(damping=0.0, friction=0.0), wrist_3_joint=dict(damping=0.0, friction=0.0)))}
force_abs_paths:=false
">

Expand All @@ -73,6 +74,7 @@
kinematics_parameters_file="${kinematics_parameters_file}"
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"
joint_dynamics="${joint_dynamics}"
force_abs_paths="${force_abs_paths}"/>

<!-- links - main serial chain -->
Expand Down Expand Up @@ -228,7 +230,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_pan_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_pan_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${shoulder_pan_damping}" friction="${shoulder_pan_friction}"/>
</joint>
<joint name="${tf_prefix}shoulder_lift_joint" type="revolute">
<parent link="${tf_prefix}shoulder_link" />
Expand All @@ -240,7 +242,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_lift_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_lift_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${shoulder_lift_damping}" friction="${shoulder_lift_friction}"/>
</joint>
<joint name="${tf_prefix}elbow_joint" type="revolute">
<parent link="${tf_prefix}upper_arm_link" />
Expand All @@ -252,7 +254,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${elbow_joint_lower_limit + safety_pos_margin}" soft_upper_limit="${elbow_joint_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${elbow_joint_damping}" friction="${elbow_joint_friction}"/>
</joint>
<joint name="${tf_prefix}wrist_1_joint" type="revolute">
<parent link="${tf_prefix}forearm_link" />
Expand All @@ -264,7 +266,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_1_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_1_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${wrist_1_damping}" friction="${wrist_1_friction}"/>
</joint>
<joint name="${tf_prefix}wrist_2_joint" type="revolute">
<parent link="${tf_prefix}wrist_1_link" />
Expand All @@ -276,7 +278,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_2_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_2_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${wrist_2_damping}" friction="${wrist_2_friction}"/>
</joint>
<joint name="${tf_prefix}wrist_3_joint" type="revolute">
<parent link="${tf_prefix}wrist_2_link" />
Expand All @@ -288,7 +290,7 @@
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
<dynamics damping="${wrist_3_damping}" friction="${wrist_3_friction}"/>
</joint>

<link name="${tf_prefix}ft_frame"/>
Expand Down
Loading