소스 검색

更新guguji.urdf文件,使其可以在rivz中正常进行关节控制

corvin_zhang 1 주 전
부모
커밋
e469246eb7
1개의 변경된 파일94개의 추가작업 그리고 90개의 파일을 삭제
  1. 94 90
      guguji_ros2_ws/src/guguji_ros2/urdf/guguji.urdf

+ 94 - 90
guguji_ros2_ws/src/guguji_ros2/urdf/guguji.urdf

@@ -5,7 +5,8 @@
 <!-- 为了适配 ROS 2 Humble 仿真,这里仅对导出结果做了少量必要修正:
      1. mesh 资源路径统一改到 guguji_ros2 包名下;
      2. 修正左髋关节名拼写;
-     3. 将右踝俯仰关节改为与左侧一致的 revolute,避免仿真中单侧连续转动。 -->
+     3. 将右踝俯仰关节改为与左侧一致的 revolute,避免仿真中单侧连续转动。
+     4. 为各个关节补充可视化调试范围,便于 joint_state_publisher_gui 在 RViz 中驱动模型。 -->
 <robot
   name="guguji">
   <link
@@ -88,23 +89,26 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="left_hip_pitch_joint"
-    type="revolute">
+  <joint
+    name="left_hip_pitch_joint"
+    type="revolute">
     <origin
       xyz="0.0212 0.075 -0.045"
       rpy="0 0 0" />
     <parent
       link="base_link" />
-    <child
-      link="left_hip_pitch_link" />
-    <axis
-      xyz="-1 0 -8.3367E-05" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="left_hip_pitch_link" />
+    <axis
+      xyz="-1 0 -8.3367E-05" />
+    <!-- SolidWorks 导出时把关节范围都写成了 0~0,
+         这样 GUI 的滑块、Random、Center 都不会产生动作。
+         这里先给一组用于 RViz/Gazebo 调试的临时范围,后续可按真实机构极限再细化。 -->
+    <limit
+      lower="-1.0"
+      upper="1.0"
+      effort="10.0"
+      velocity="2.0" />
   </joint>
   <link
     name="left_knee_pitch_link">
@@ -146,23 +150,23 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="left_knee_pitch_joint"
-    type="revolute">
+  <joint
+    name="left_knee_pitch_joint"
+    type="revolute">
     <origin
       xyz="-0.0207 0.086 -0.065"
       rpy="0 -8.3367E-05 0" />
     <parent
       link="left_hip_pitch_link" />
-    <child
-      link="left_knee_pitch_link" />
-    <axis
-      xyz="0 -1 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="left_knee_pitch_link" />
+    <axis
+      xyz="0 -1 0" />
+    <limit
+      lower="-1.2"
+      upper="1.2"
+      effort="10.0"
+      velocity="2.0" />
   </joint>
   <link
     name="left_ankle_pitch_link">
@@ -204,23 +208,23 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="left_ankle_pitch_joint"
-    type="revolute">
+  <joint
+    name="left_ankle_pitch_joint"
+    type="revolute">
     <origin
       xyz="-0.10001 -0.068602 -0.064992"
       rpy="0 0 0" />
     <parent
       link="left_knee_pitch_link" />
-    <child
-      link="left_ankle_pitch_link" />
-    <axis
-      xyz="0 -1 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="left_ankle_pitch_link" />
+    <axis
+      xyz="0 -1 0" />
+    <limit
+      lower="-0.8"
+      upper="0.8"
+      effort="8.0"
+      velocity="2.0" />
   </joint>
   <link
     name="left_foot_link">
@@ -262,23 +266,23 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="left_ankle_joint"
-    type="revolute">
+  <joint
+    name="left_ankle_joint"
+    type="revolute">
     <origin
       xyz="0.04999 0.068602 -0.115"
       rpy="0 0 0" />
     <parent
       link="left_ankle_pitch_link" />
-    <child
-      link="left_foot_link" />
-    <axis
-      xyz="0 -1 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="left_foot_link" />
+    <axis
+      xyz="0 -1 0" />
+    <limit
+      lower="-0.6"
+      upper="0.6"
+      effort="8.0"
+      velocity="2.0" />
   </joint>
   <link
     name="right_hip_pitch_link">
@@ -320,23 +324,23 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="right_hip_pitch_joint"
-    type="revolute">
+  <joint
+    name="right_hip_pitch_joint"
+    type="revolute">
     <origin
       xyz="0.0212 -0.075 -0.045"
       rpy="0 -8.3367E-05 0" />
     <parent
       link="base_link" />
-    <child
-      link="right_hip_pitch_link" />
-    <axis
-      xyz="1 0 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="right_hip_pitch_link" />
+    <axis
+      xyz="1 0 0" />
+    <limit
+      lower="-1.0"
+      upper="1.0"
+      effort="10.0"
+      velocity="2.0" />
   </joint>
   <link
     name="right_knee_pitch_link">
@@ -378,23 +382,23 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="right_knee_pitch_joint"
-    type="revolute">
+  <joint
+    name="right_knee_pitch_joint"
+    type="revolute">
     <origin
       xyz="-0.020705 -0.0864 -0.064998"
       rpy="0 0 0" />
     <parent
       link="right_hip_pitch_link" />
-    <child
-      link="right_knee_pitch_link" />
-    <axis
-      xyz="0 1 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+    <child
+      link="right_knee_pitch_link" />
+    <axis
+      xyz="0 1 0" />
+    <limit
+      lower="-1.2"
+      upper="1.2"
+      effort="10.0"
+      velocity="2.0" />
   </joint>
   <link
     name="right_ankle_pitch_link">
@@ -449,10 +453,10 @@
     <axis
       xyz="0 1 0" />
     <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
+      lower="-0.8"
+      upper="0.8"
+      effort="8.0"
+      velocity="2.0" />
   </joint>
   <link
     name="right_foot_link">
@@ -494,22 +498,22 @@
       </geometry>
     </collision>
   </link>
-  <joint
-    name="right_ankle_joint"
-    type="revolute">
+  <joint
+    name="right_ankle_joint"
+    type="revolute">
     <origin
       xyz="0.04999 -0.069002 -0.115"
       rpy="0 0 0" />
     <parent
       link="right_ankle_pitch_link" />
-    <child
-      link="right_foot_link" />
-    <axis
-      xyz="0 1 0" />
-    <limit
-      lower="0"
-      upper="0"
-      effort="0"
-      velocity="0" />
-  </joint>
+    <child
+      link="right_foot_link" />
+    <axis
+      xyz="0 1 0" />
+    <limit
+      lower="-0.6"
+      upper="0.6"
+      effort="8.0"
+      velocity="2.0" />
+  </joint>
 </robot>