gazebo显示完成
This commit is contained in:
@@ -2,7 +2,14 @@
|
||||
<robot name="robotic_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:include filename="$(find robotic_arm)/urdf/materials.xacro" />
|
||||
|
||||
<!-- 底座连杆 -->
|
||||
|
||||
<link name="world" />
|
||||
<joint name="world_to_base" type="fixed">
|
||||
<parent link="world" />
|
||||
<child link="base_link" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -24,18 +31,16 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节1:底座旋转 -->
|
||||
<joint name="joint1" type="revolute">
|
||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
<parent link="base_link" />
|
||||
<child link="link1" />
|
||||
<axis xyz="0.0 0.0 1.0" />
|
||||
<limit lower="-3.14159" upper="3.14159" effort="100.0" velocity="1.0" />
|
||||
<!-- 阻尼系数和摩擦系数,模拟运动阻力和摩擦力 -->
|
||||
|
||||
<dynamics damping="0.1" friction="0.1" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆1 -->
|
||||
<link name="link1">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -57,18 +62,18 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节2:肩部俯仰 -->
|
||||
|
||||
<joint name="joint2" type="revolute">
|
||||
<parent link="link1" />
|
||||
<child link="link2" />
|
||||
<origin xyz="0.0 0.0 0.15" rpy="0.0 0.0 0.0" />
|
||||
<axis xyz="0.0 1.0 0.0" />
|
||||
<limit lower="-1.5708" upper="1.5708" effort="100.0" velocity="1.0" />
|
||||
<!-- 阻尼系数和摩擦系数,模拟运动阻力和摩擦力 -->
|
||||
|
||||
<dynamics damping="0.1" friction="0.1" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆2 -->
|
||||
|
||||
<link name="link2">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -90,7 +95,7 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节3: 肘部俯仰 -->
|
||||
|
||||
<joint name="joint3" type="revolute">
|
||||
<parent link="link2" />
|
||||
<child link="link3" />
|
||||
@@ -100,7 +105,7 @@
|
||||
<dynamics damping="0.1" friction="0.1" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆3 -->
|
||||
|
||||
<link name="link3">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -122,7 +127,7 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节4: 腕部滚转 -->
|
||||
|
||||
<joint name="joint4" type="revolute">
|
||||
<parent link="link3" />
|
||||
<child link="link4" />
|
||||
@@ -132,7 +137,7 @@
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆4 -->
|
||||
|
||||
<link name="link4">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -154,7 +159,7 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节5: 腕部俯仰 -->
|
||||
|
||||
<joint name="joint5" type="revolute">
|
||||
<parent link="link4" />
|
||||
<child link="link5" />
|
||||
@@ -164,7 +169,7 @@
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆5 -->
|
||||
|
||||
<link name="link5">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -186,7 +191,6 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节6: 腕部偏航 -->
|
||||
<joint name="joint6" type="revolute">
|
||||
<parent link="link5" />
|
||||
<child link="link6" />
|
||||
@@ -196,7 +200,7 @@
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆6 (末端执行器) -->
|
||||
|
||||
<link name="link6">
|
||||
<visual>
|
||||
<geometry>
|
||||
@@ -218,7 +222,7 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 末端执行器固定关节 -->
|
||||
|
||||
<joint name="end_effector_fixed" type="fixed">
|
||||
<parent link="link6" />
|
||||
<child link="end_effector" />
|
||||
@@ -228,14 +232,14 @@
|
||||
<link name="end_effector" />
|
||||
|
||||
|
||||
<!-- gazebo 插件 -->
|
||||
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/six_axis_arm</robotNamespace>
|
||||
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
||||
<parameters>$(find robotic_arm)/config/controllers.yaml</parameters>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Gazebo 颜色设置 -->
|
||||
|
||||
<gazebo reference="base_link">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
@@ -258,72 +262,63 @@
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- 传动装置 -->
|
||||
<transmission name="trans1">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<ros2_control name="robotic_arm" type="system">
|
||||
<hardware>
|
||||
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
||||
</hardware>
|
||||
|
||||
<joint name="joint1">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-3.14159</param>
|
||||
<param name="max">3.14159</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor1">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="trans2">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint2">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-1.5708</param>
|
||||
<param name="max">1.5708</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor2">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="trans3">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint3">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-1.5708</param>
|
||||
<param name="max">1.5708</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor3">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="trans4">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint4">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-3.14159</param>
|
||||
<param name="max">3.14159</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor4">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="trans5">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint5">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-1.5708</param>
|
||||
<param name="max">1.5708</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor5">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="trans6">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint6">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<command_interface name="position">
|
||||
<param name="min">-3.14159</param>
|
||||
<param name="max">3.14159</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
<actuator name="motor6">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
|
||||
</ros2_control>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user