机械臂仿真构建完成
This commit is contained in:
329
simulation_ws/robotic_arm/urdf/robotic_arm.urdf.xacro
Normal file
329
simulation_ws/robotic_arm/urdf/robotic_arm.urdf.xacro
Normal file
@@ -0,0 +1,329 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="robotic_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:include filename="$(find robotic_arm)/urdf/materials.xacro" />
|
||||
|
||||
<!-- 底座连杆 -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder radius="0.1" length="0.05" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.025" rpy="0.0 0.0 0.0" />
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder radius="0.1" length="0.05" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.025" rpy="0.0 0.0 0.0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="1.0" />
|
||||
<origin xyz="0.0 0.0 0.025" />
|
||||
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
|
||||
</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>
|
||||
<box size="0.08 0.08 0.15" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.075" rpy="0.0 0.0 0.0" />
|
||||
<material name="blue" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.08 0.08 0.15" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.075" rpy="0.0 0.0 0.0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.8" />
|
||||
<origin xyz="0 0 0.075" />
|
||||
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.003" />
|
||||
</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>
|
||||
<box size="0.06 0.06 0.20" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.10" rpy="0.0 0.0 0.0" />
|
||||
<material name="orange" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.06 0.06 0.20" />
|
||||
</geometry>
|
||||
<origin xyz="0.0 0.0 0.10" rpy="0.0 0.0 0.0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.6" />
|
||||
<origin xyz="0 0 0.10" />
|
||||
<inertia ixx="0.003" ixy="0" ixz="0" iyy="0.003" iyz="0" izz="0.002" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节3: 肘部俯仰 -->
|
||||
<joint name="joint3" type="revolute">
|
||||
<parent link="link2" />
|
||||
<child link="link3" />
|
||||
<origin xyz="0 0 0.20" rpy="0 0 0" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="-1.5708" upper="1.5708" effort="80" velocity="1.0" />
|
||||
<dynamics damping="0.1" friction="0.1" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆3 -->
|
||||
<link name="link3">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.055 0.055 0.18" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.09" rpy="0 0 0" />
|
||||
<material name="blue" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.055 0.055 0.18" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.09" rpy="0 0 0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.5" />
|
||||
<origin xyz="0 0 0.09" />
|
||||
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节4: 腕部滚转 -->
|
||||
<joint name="joint4" type="revolute">
|
||||
<parent link="link3" />
|
||||
<child link="link4" />
|
||||
<origin xyz="0 0 0.18" rpy="0 0 0" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="-3.14159" upper="3.14159" effort="50" velocity="1.5" />
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆4 -->
|
||||
<link name="link4">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 0.14" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.07" rpy="0 0 0" />
|
||||
<material name="orange" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 0.14" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.07" rpy="0 0 0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.3" />
|
||||
<origin xyz="0 0 0.07" />
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节5: 腕部俯仰 -->
|
||||
<joint name="joint5" type="revolute">
|
||||
<parent link="link4" />
|
||||
<child link="link5" />
|
||||
<origin xyz="0 0 0.14" rpy="0 0 0" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="-1.5708" upper="1.5708" effort="30" velocity="1.5" />
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆5 -->
|
||||
<link name="link5">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.045 0.045 0.10" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
||||
<material name="blue" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.045 0.045 0.10" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.05" rpy="0 0 0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.2" />
|
||||
<origin xyz="0 0 0.05" />
|
||||
<inertia ixx="0.0005" ixy="0" ixz="0" iyy="0.0005" iyz="0" izz="0.0003" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 关节6: 腕部偏航 -->
|
||||
<joint name="joint6" type="revolute">
|
||||
<parent link="link5" />
|
||||
<child link="link6" />
|
||||
<origin xyz="0 0 0.10" rpy="0 0 0" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="-3.14159" upper="3.14159" effort="20" velocity="2.0" />
|
||||
<dynamics damping="0.05" friction="0.05" />
|
||||
</joint>
|
||||
|
||||
<!-- 连杆6 (末端执行器) -->
|
||||
<link name="link6">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.06" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder radius="0.03" length="0.06" />
|
||||
</geometry>
|
||||
<origin xyz="0 0 0.03" rpy="0 0 0" />
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.1" />
|
||||
<origin xyz="0 0 0.03" />
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<!-- 末端执行器固定关节 -->
|
||||
<joint name="end_effector_fixed" type="fixed">
|
||||
<parent link="link6" />
|
||||
<child link="end_effector" />
|
||||
<origin xyz="0 0 0.06" rpy="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<link name="end_effector" />
|
||||
|
||||
|
||||
<!-- gazebo 插件 -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/six_axis_arm</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Gazebo 颜色设置 -->
|
||||
<gazebo reference="base_link">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link1">
|
||||
<material>Gazebo/Blue</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link2">
|
||||
<material>Gazebo/Orange</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link3">
|
||||
<material>Gazebo/Blue</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link4">
|
||||
<material>Gazebo/Orange</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link5">
|
||||
<material>Gazebo/Blue</material>
|
||||
</gazebo>
|
||||
<gazebo reference="link6">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- 传动装置 -->
|
||||
<transmission name="trans1">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint1">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</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>
|
||||
</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>
|
||||
</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>
|
||||
</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>
|
||||
</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>
|
||||
</joint>
|
||||
<actuator name="motor6">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user