diff --git a/robots/anymal_b_simple_description/robots/anymal-kinova.urdf b/robots/anymal_b_simple_description/robots/anymal-kinova.urdf
index b5e2bb5a0e3993661f2e3ece146db99aea593f99..450422461c1a463d4cb6d8ffd652a775c71e72c3 100644
--- a/robots/anymal_b_simple_description/robots/anymal-kinova.urdf
+++ b/robots/anymal_b_simple_description/robots/anymal-kinova.urdf
@@ -904,7 +904,7 @@
             <inertia ixx="0.00152031725204" ixy="0" ixz="0" iyy="0.00152031725204" iyz="0" izz="0.00059816"/>
         </inertial>
     </link>
-    <joint name="j2s6s200_joint_1" type="continuous">
+    <joint name="j2s6s200_joint_1" type="revolute">
         <parent link="j2s6s200_link_base"/>
         <child link="j2s6s200_link_1"/>
         <axis xyz="0 0 1"/>
@@ -1033,7 +1033,7 @@
             <inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="0.0004321316048" iyz="0" izz="9.26e-05"/>
         </inertial>
     </link>
-    <joint name="j2s6s200_joint_4" type="continuous">
+    <joint name="j2s6s200_joint_4" type="revolute">
         <parent link="j2s6s200_link_3"/>
         <child link="j2s6s200_link_4"/>
         <axis xyz="0 0 1"/>
@@ -1119,7 +1119,7 @@
             <inertia ixx="0.0003453236187" ixy="0" ixz="0" iyy="0.0003453236187" iyz="0" izz="0.0005816"/>
         </inertial>
     </link>
-    <joint name="j2s6s200_joint_6" type="continuous">
+    <joint name="j2s6s200_joint_6" type="revolute">
         <parent link="j2s6s200_link_5"/>
         <child link="j2s6s200_link_6"/>
         <axis xyz="0 0 1"/>
diff --git a/robots/anymal_b_simple_description/srdf/anymal-kinova.srdf b/robots/anymal_b_simple_description/srdf/anymal-kinova.srdf
index 72df5d3f8735cb1d6da5ce7b3f78908adcddf03f..6743cdcbb3951328c3aa18c41c4924bcb60222de 100644
--- a/robots/anymal_b_simple_description/srdf/anymal-kinova.srdf
+++ b/robots/anymal_b_simple_description/srdf/anymal-kinova.srdf
@@ -92,12 +92,12 @@
         <joint name="RH_HAA" value="0.1" />
         <joint name="RH_HFE" value="-0.7" />
         <joint name="RH_KFE" value="1." />
-        <joint name="j2s6s200_joint_1" value="1.5707" />
-        <joint name="j2s6s200_joint_2" value="2.618" />
-        <joint name="j2s6s200_joint_3" value="-1.5707" />
-        <joint name="j2s6s200_joint_4" value="3.1415" />
-        <joint name="j2s6s200_joint_5" value="2.618" />
-        <joint name="j2s6s200_joint_6" value="0." />
+        <joint name="j2s6s200_joint_1" value="4.71238898038469" /><!-- 3Ï€ / 2 -->
+        <joint name="j2s6s200_joint_2" value="3.665191429188092" /><!-- 7Ï€ / 6 -->
+        <joint name="j2s6s200_joint_3" value="1.0471975511965976" /><!-- 1Ï€ / 3 -->
+        <joint name="j2s6s200_joint_4" value="0.0" />
+        <joint name="j2s6s200_joint_5" value="2.0943951023931953" /><!-- 2Ï€ / 3 -->
+        <joint name="j2s6s200_joint_6" value="0.0" />
     </group_state>
 
     <disable_collisions link1="LF_HIP" link2="LF_THIGH" reason="Adjacent" />