diff --git a/config/joint_dynamics.yaml b/config/joint_dynamics.yaml
new file mode 100644
index 0000000..a03f929
--- /dev/null
+++ b/config/joint_dynamics.yaml
@@ -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
diff --git a/test/test_joint_dynamics.yaml b/test/test_joint_dynamics.yaml
new file mode 100644
index 0000000..4b4e4bf
--- /dev/null
+++ b/test/test_joint_dynamics.yaml
@@ -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
diff --git a/urdf/inc/ur_common.xacro b/urdf/inc/ur_common.xacro
index a763e78..5d78b60 100644
--- a/urdf/inc/ur_common.xacro
+++ b/urdf/inc/ur_common.xacro
@@ -41,7 +41,7 @@
-
+
@@ -49,6 +49,7 @@
+
@@ -57,6 +58,7 @@
+
@@ -84,6 +86,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/urdf/ur.urdf.xacro b/urdf/ur.urdf.xacro
index 0ec2c4e..51a471b 100644
--- a/urdf/ur.urdf.xacro
+++ b/urdf/ur.urdf.xacro
@@ -23,6 +23,11 @@
+
+
+
+
+
@@ -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)"
>
diff --git a/urdf/ur_macro.xacro b/urdf/ur_macro.xacro
index 39c094d..9b3052b 100644
--- a/urdf/ur_macro.xacro
+++ b/urdf/ur_macro.xacro
@@ -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
">
@@ -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}"/>
@@ -228,7 +230,7 @@
-
+
@@ -240,7 +242,7 @@
-
+
@@ -252,7 +254,7 @@
-
+
@@ -264,7 +266,7 @@
-
+
@@ -276,7 +278,7 @@
-
+
@@ -288,7 +290,7 @@
-
+