ROS——六轴机械臂建模

创建工作空间及目录(my_arm)

  • 创建launch、urdf文件夹
    在这里插入图片描述

  • urdf
    在这里插入图片描述

  • launch
    在这里插入图片描述

Arm_Model.xacro

<?xml version="1.0"?>
<robot name="marm" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!-- Defining the colors used in this robot -->
    <material name="Black">
        <color rgba="0 0 0 1"/>
    </material>
    <material name="White">
        <color rgba="1 1 1 1"/>
    </material>
    <material name="Blue">
        <color rgba="0 0 1 1"/>
    </material>
    <material name="Red">
        <color rgba="1 0 0 1"/>
    </material>

    <!-- Constants -->
    <xacro:property name="M_PI" value="3.14159"/>

    <!-- link1 properties -->
    <xacro:property name="link0_radius" value="0.05" />
    <xacro:property name="link0_length" value="0.04" />
    <xacro:property name="link0_mass" value="1" />

    <!-- link1 properties -->
    <xacro:property name="link1_radius" value="0.03" />
    <xacro:property name="link1_length" value="0.10" />
    <xacro:property name="link1_mass" value="1" />

    <!-- link2 properties -->
    <xacro:property name="link2_radius" value="0.03" />
    <xacro:property name="link2_length" value="0.14" />
    <xacro:property name="link2_mass" value="0.8" />

    <!-- link3 properties -->
    <xacro:property name="link3_radius" value="0.03" />
    <xacro:property name="link3_length" value="0.15" />
    <xacro:property name="link3_mass" value="0.8" />

    <!-- link4 properties -->
    <xacro:property name="link4_radius" value="0.025" />
    <xacro:property name="link4_length" value="0.06" />
    <xacro:property name="link4_mass" value="0.7" />

    <!-- link5 properties -->
    <xacro:property name="link5_radius" value="0.03" />
    <xacro:property name="link5_length" value="0.06" />
    <xacro:property name="link5_mass" value="0.7" />

    <!-- link6 properties -->
    <xacro:property name="link6_radius" value="0.04" />
    <xacro:property name="link6_length" value="0.02" />
    <xacro:property name="link6_mass" value="0.6" />

    <!-- gripper -->
    <!-- 夹爪 -->
    <xacro:property name="gripper_length" value="0.03" />
    <xacro:property name="gripper_width" value="0.01" />
    <xacro:property name="gripper_height" value="0.06" />
    <xacro:property name="gripper_mass" value="0.5" />

    <!-- Gripper frame -->
    <xacro:property name="grasp_frame_radius" value="0.001" />

    <!-- Macro for inertia matrix -->
    <!-- 定义宏macro,宏里的函数名为cylinder_inertial_matrix,参数为"m r h",关于惯性矩阵的宏-->
    <xacro:macro name="cylinder_inertial_matrix" params="m r h">
        <inertial>
            <mass value="${m}" />
            <!-- 圆柱体惯性矩阵的标准计算公式 -->
            <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
                iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
                izz="${m*r*r/2}" /> 
        </inertial>
    </xacro:macro>

    <xacro:macro name="box_inertial_matrix" params="m w h d">
        <inertial>
            <mass value="${m}" />
            <!-- 长方体惯性矩阵的标准计算公式 -->
            <inertia ixx="${m*(h*h+d*d)/12}" ixy = "0" ixz = "0"
                iyy="${m*(w*w+d*d)/12}" iyz = "0"
                izz="${m*(w*w+h*h)/12}" /> 
        </inertial>
    </xacro:macro>

    <!-- /   ARM BASE    // -->
    <!-- 底盘 -->
    <!-- base-link可以不需要碰撞检测和惯性矩阵两个模块内容 -->
    <link name="base_link">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <box size="0.001 0.001 0.001" />
            </geometry>
        </visual>
    </link>

    <joint name="base_joint" type="fixed">
        <origin xyz="0 0 ${link0_length/2}" rpy="0 0 0" />        
        <parent link="base_link"/>
        <child link="link0" />
    </joint>

    <!-- /    LINK0    // -->
    <link name="link0">
        <!-- visual:可视化部分 -->
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link0_radius}" length="${link0_length}"/>
            </geometry>
            <material name="White" />
        </visual>
        <!-- collision:碰撞检测部分 -->
        <!-- collision的物理模型和坐标与visual部分保持一致 -->
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link0_radius}" length="${link0_length}"/>
            </geometry>
        </collision>
        <!-- 通过函数名cylinder_inertial_matrix来调用之前定义的用来计算惯性矩阵的宏 -->
        <cylinder_inertial_matrix m="${link0_mass}" r="${link0_radius}" h="${link0_length}"/>
    </link>

    <joint name="joint1" type="revolute">
        <parent link="link0"/>
        <child link="link1"/>
        <origin xyz="0 0 ${link0_length/2}" rpy="0 ${M_PI/2} 0" />
        <axis xyz="-1 0 0" />
        <!-- 关节限制 -->
        <!-- effort:关节受力极限 -->
        <!-- velocity:最大速度 -->
        <!-- lower/upper:最大旋转角度(弧度制) -->
        <limit effort="300" velocity="1" lower="${-M_PI}" upper="${M_PI}"/>
    </joint>

    <!-- /   LINK1  // -->
    <link name="link1" >
        <visual>
            <origin xyz="-${link1_length/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link1_radius}" length="${link1_length}"/>
            </geometry>
            <material name="Blue" />
        </visual>
        <collision>
            <origin xyz="-${link1_length/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link1_radius}" length="${link1_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link1_mass}" r="${link1_radius}" h="${link1_length}"/>
    </link>

    <joint name="joint2" type="revolute">
        <parent link="link1"/>
        <child link="link2"/>
        <origin xyz="-${link1_length} 0 0.0" rpy="-${M_PI/2} 0 ${M_PI/2}" />
        <axis xyz="1 0 0" />
        <limit effort="300" velocity="1" lower="${-M_PI}" upper="${M_PI}" />
    </joint>

    <!-- ///   LINK2  // -->
    <link name="link2" >
        <visual>
            <origin xyz="0 0 ${link2_length/2}" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link2_radius}" length="${link2_length}"/>
            </geometry>
            <material name="White" />
        </visual>

        <collision>
            <origin xyz="0 0 ${link2_length/2}" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link2_radius}" length="${link2_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link2_mass}" r="${link2_radius}" h="${link2_length}"/>
    </link>

    <joint name="joint3" type="revolute">
        <parent link="link2"/>
        <child link="link3"/>
        <origin xyz="0 0 ${link2_length}" rpy="0 ${M_PI} 0" />
        <axis xyz="-1 0 0" />
        <limit effort="300" velocity="1" lower="${-M_PI}" upper="${M_PI}" />
    </joint>

    <!-- /   LINK3  / -->
    <link name="link3" >
        <visual>
            <origin xyz="0 0 -${link3_length/2}" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link3_radius}" length="${link3_length}"/>
            </geometry>
            <material name="Blue" />
        </visual>
        <collision>
            <origin xyz="0 0 -${link3_length/2}" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link3_radius}" length="${link3_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link3_mass}" r="${link3_radius}" h="${link3_length}"/>
    </link>

    <joint name="joint4" type="revolute">
        <parent link="link3"/>
        <child link="link4"/>
        <origin xyz="0.0 0.0 -${link3_length}" rpy="0 ${M_PI/2} ${M_PI}" />
        <axis xyz="1 0 0" />
        <limit effort="300" velocity="1" lower="${-M_PI}" upper="${M_PI}" />
    </joint>

    <!-- ///   LINK4   -->
    <link name="link4" >
        <visual>
            <origin xyz="${link4_length/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link4_radius}" length="${link4_length}"/>
            </geometry>
            <material name="Black" />
        </visual>
        <collision>
            <origin xyz="${link4_length/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link4_radius}" length="${link4_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link4_mass}" r="${link4_radius}" h="${link4_length}"/>
    </link>

    <!-- revolute:带上下限的旋转关节 -->
    <joint name="joint5" type="revolute">
        <parent link="link4"/>
        <child link="link5"/>
        <origin xyz="${link4_length} 0.0 0.0" rpy="0 ${M_PI/2} 0" />
        <axis xyz="1 0 0" />
        <limit effort="300" velocity="1" lower="${-M_PI}" upper="${M_PI}" />
    </joint>

    <!-- //   LINK5  / -->
    <link name="link5">
        <visual>
            <origin xyz="0 0 ${link4_length/2}" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link5_radius}" length="${link5_length}"/>
            </geometry>
            <material name="White" />
        </visual>
        <collision>
            <origin xyz="0 0 ${link4_length/2} " rpy="0 0 0" />
            <geometry>
                <cylinder radius="${link5_radius}" length="${link5_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link5_mass}" r="${link5_radius}" h="${link5_length}"/>
    </link>

    <joint name="joint6" type="revolute">
        <parent link="link5"/>
        <child link="link6"/>
        <origin xyz="0 0 ${link4_length}" rpy="${1.5*M_PI} -${M_PI/2} 0" />
        <axis xyz="1 0 0" />
        <limit effort="300" velocity="1" lower="${-2*M_PI}" upper="${2*M_PI}" />
    </joint>

    <!--    LINK6  / -->
    <link name="link6">
        <visual>
            <origin xyz="${link6_length/2} 0 0 " rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link6_radius}" length="${link6_length}"/>
            </geometry>
            <material name="Blue" />
        </visual>
        <collision>
            <origin xyz="${link6_length/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <cylinder radius="${link6_radius}" length="${link6_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix m="${link6_mass}" r="${link6_radius}" h="${link6_length}"/>
    </link>

    <!-- prismatic:带上下限的直线平移关节 -->
    <joint name="finger_joint1" type="prismatic">
        <parent link="link6"/>
        <child link="gripper_finger_link1"/>
        <origin xyz="${link6_length} -0.03 0" rpy="0 0 0" />
        <axis xyz="0 1 0" />
        <limit effort="100" lower="0" upper="0.06" velocity="0.02"/>
    </joint>

    <!-- //   gripper   // -->
    <!-- LEFT GRIPPER AFT LINK -->
    <link name="gripper_finger_link1">
        <visual>
            <origin xyz="${gripper_height/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <box size="${gripper_length} ${gripper_width} ${gripper_height}" />
            </geometry>
            <material name="White" />
        </visual>
        <collision>
            <origin xyz="${gripper_height/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <box size="${gripper_length} ${gripper_width} ${gripper_height}" />
            </geometry>
        </collision>
        <box_inertial_matrix m="${gripper_mass}" w="${gripper_width}" h="${gripper_height}" d="${gripper_length}"/>
    </link>

    <joint name="finger_joint2" type="fixed">
        <parent link="link6"/>
        <child link="gripper_finger_link2"/>
        <origin xyz="${link6_length} 0.03 0" rpy="0 0 0" />
    </joint>

    <!-- RIGHT GRIPPER AFT LINK -->
    <link name="gripper_finger_link2">
        <visual>
            <origin xyz="${gripper_height/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <box size="${gripper_length} ${gripper_width} ${gripper_height}" />
            </geometry>
            <material name="White" />
        </visual>
        <collision>
            <origin xyz="${gripper_height/2} 0 0" rpy="0 ${M_PI/2} 0" />
            <geometry>
                <box size="${gripper_length} ${gripper_width} ${gripper_height}" />
            </geometry>
        </collision>
        <box_inertial_matrix m="${gripper_mass}" w="${gripper_width}" h="${gripper_height}" d="${gripper_length}"/>
    </link>

    <!-- Grasping frame -->
    <link name="grasping_frame"/>

    <joint name="grasping_frame_joint" type="fixed">
        <parent link="link6"/>
        <child link="grasping_frame"/>
        <origin xyz="${gripper_height} 0 0" rpy="0 0 0"/>
    </joint>

</robot>

Display_Model.launch

<launch>
    <arg name="model" />
    <!-- 加载机器人模型参数(机器人模型路径保存在robot_description变量中,后续访问这个变量就可以获取该路径) -->
    <param name="robot_description" command="$(find xacro)/xacro --inorder $(find my_arm)/urdf/Arm_Model.xacro" />

    <!-- 设置GUI参数,显示关节滑动条控制插件 -->
    <param name="use_gui" value="true"/>

    <!-- 运行joint_state_publisher节点,发布机器人的关节状态(发布关节角度)  -->
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    
    <!-- 运行robot_state_publisher节点,发布tf坐标系变换  -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

    <!-- 运行rviz可视化界面 -->
    <node name="rviz" pkg="rviz" type="rviz" args="-d $(find my_arm)/urdf.rviz" required="true" />
</launch>

启动 launch 文件

  • roslaunch my_arm Display_Model.launch

问题一: Resource not found: xacro

sudo apt-get install ros-melodic-xacro即可

问题二:

ERROR: cannot launch node of type [joint_state_publisher/joint_state_publisher]: joint_state_publisher
ROS path [0]=/opt/ros/noetic/share/ros
ROS path [1]=/home/vodka/vodka_ws/src
ROS path [2]=/opt/ros/noetic/share

ERROR: cannot launch node of type [robot_state_publisher/state_publisher]: robot_state_publisher
ROS path [0]=/opt/ros/noetic/share/ros
ROS path [1]=/home/vodka/vodka_ws/src
ROS path [2]=/opt/ros/noetic/share

  • 解决方案:
  • 查看launch文件中type的名字是否正确
  • sudo apt-get install ros-noetic-joint-state-publisher(添加相关依赖包)

问题三:RVIZ界面没有显示控制滚动条

  • 解决方案: sudo apt-get install ros-noetic-joint-state-publisher-gui
  • 将launch文件中的 joint_state_publisher 改为 joint_state_publisher_gui

六轴机械臂

在这里插入图片描述
在这里插入图片描述

  • 20
    点赞
  • 13
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值