Skip to content
Snippets Groups Projects
Commit bbbaf610 authored by ipa-nhg's avatar ipa-nhg
Browse files

Add optional safety_controller tags for e series descriptions

parent c0494acf
No related branches found
No related tags found
No related merge requests found
......@@ -25,7 +25,10 @@
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false safety_pos_margin:=0.15
safety_k_position:=20">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
......@@ -94,9 +97,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="330.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -127,9 +136,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="330.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -160,9 +175,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -193,9 +214,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -226,9 +253,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -259,9 +292,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......
......@@ -24,7 +24,10 @@
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false safety_pos_margin:=0.15
safety_k_position:=20">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
......@@ -93,9 +96,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="330.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -126,9 +135,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="330.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -159,9 +174,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -192,9 +213,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -225,9 +252,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -258,9 +291,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="54.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......
......@@ -20,7 +20,10 @@
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false safety_pos_margin:=0.15
safety_k_position:=20">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
......@@ -110,9 +113,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="150.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -143,9 +152,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="150.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -176,9 +191,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.14"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.14"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -209,9 +230,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="28.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -242,9 +269,15 @@
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="28.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......@@ -275,9 +308,15 @@
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="6.28"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="28.0" velocity="6.28"/>
<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>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment