《ROS理论与实践》学习笔记构建机器人仿真平台

Posted Sakurazzy

tags:

篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了《ROS理论与实践》学习笔记构建机器人仿真平台相关的知识,希望对你有一定的参考价值。

在学习《ROS理论与实践》课程时,记录了学习过程中的编程练习,课后作业以及发现的问题,后续会对尚未解决的问题继续分析并更新,纯小白,仅供参考。
本次学习笔记关于课程中的第六讲:构建机器人仿真平台 。主要学习了ROS的xacro建模方法和gazebo仿真。


课程内容

1.优化物理仿真模型

1.使用xacro模型文件进行机器人建模

xacro模型文件更加简洁,提供可编程接口

  • 常量定义
    < xacro:property name=“xxx” value=“xxx”/>
  • 宏定义
    < xacro:macro name=“xxx” params=“xxx”>

    < /xacro:macro>
  • 宏调用
    < name A=“xxx” B=“xxx” C=“xxx”/>
  • 文件包含
    < xacro:include filename="$(find 功能包名称)/路径/xxx.xacro"/>

2. ros_control

ros_control提供了一系列控制器接口、传动装置接口、硬件接口、控制器工具箱等
控制器(controllers)主要包括:

  • joint_state_controller
  • joint_effort_controller
  • joint_position_controller
  • joint_velocity_controller

具体内容参考ROS Wiki链接:ros_control

3.仿真模型的优化

  1. 为link添加惯性参数和碰撞属性
    添加< collision >以及< cylinder_inertial_matrix>标签
  2. 为link添加gazebo标签
    添加< gazebo>标签
  3. 为joint添加传动装置
    添加< transmission>标签
    具体内容参考ROS Wiki链接:urdf_transmission
  4. 添加gazebo控制器插件
    · < robotNamespace > 机器人命名空间
    · < leftJoint>< rightJoint> 左右轮转动的关节joint
    · < wheelSeparation>< wheelDiameter> 机器人模型尺寸,用于计算差速参数
    · < commandtTopic> 控制器订阅的速度控制指令
    · < odometryFrame> 里程计数据的参考坐标系

2.创建物理仿真环境

方法:

  • 直接添加环境模型
  • 使用building editor

本讲作业

1.将上讲urdf模型改写为xacro文件,进行运动控制仿真

  • 基本xacro模型文件nmybot_base_gazebo.xacro
<?xml version="1.0"?>
<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!-- PROPERTY LIST -->
    <xacro:property name="M_PI" value="3.1415926"/>
    <xacro:property name="base_mass"   value="20" /> 
    <xacro:property name="base_radius" value="0.20"/>
    <xacro:property name="base_length" value="0.05"/>

    <xacro:property name="motor_mass"   value="0.01" />
    <xacro:property name="motor_radius" value="0.04"/>
    <xacro:property name="motor_length" value="0.18"/>
    <xacro:property name="motor_joint_x" value="0.1"/>
    <xacro:property name="motor_joint_y" value="0.11"/>

    <xacro:property name="wheel_mass"   value="50" />                 <!-- to avoid the auto slip -->
    <xacro:property name="wheel_radius" value="0.06"/>
    <xacro:property name="wheel_length" value="0.025"/>
    <xacro:property name="wheel_joint_y" value="0.1025"/>
    <xacro:property name="wheel_joint_z" value="0"/>

    <xacro:property name="caster_mass"    value="0.5" /> 
    <xacro:property name="caster_radius"  value="0.0175"/>             <!-- wheel_radius - ( base_length/2 - wheel_joint_z) -->
    <xacro:property name="caster_length"  value="0.01"/>
    <xacro:property name="caster_joint_x" value="0.18"/>
    <xacro:property name="caster_joint_z" value="-0.025"/>
    <xacro:property name="caster_link_z"   value="-0.0175"/>

    <!-- Defining the colors used in this robot -->
    <material name="yellow">
        <color rgba="1 0.4 0 1"/>
    </material>
    <material name="black">
        <color rgba="0 0 0 0.95"/>
    </material>
    <material name="gray">
        <color rgba="0.75 0.75 0.75 1"/>
    </material>
    
    <!-- Macro for inertia matrix -->
    <xacro:macro name="sphere_inertial_matrix" params="m r">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
                iyy="${2*m*r*r/5}" iyz="0" 
                izz="${2*m*r*r/5}" />
        </inertial>
    </xacro:macro>

    <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>

    <!-- Macro for robot  motor -->
    <xacro:macro name="motor" params="prefix reflect">
        <joint name="${prefix}_motor_joint" type="fixed">
            <origin xyz="${-motor_joint_x} ${reflect*motor_joint_y} 0" rpy="0 0 0"/>
            <parent link="base_link"/>
            <child link="${prefix}_motor_link"/>
            <axis xyz="0 1 0"/>
        </joint>

        <link name="${prefix}_motor_link">
            <visual>
                <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
                <geometry>
                    <cylinder radius="${motor_radius}" length = "${motor_length}"/>
                </geometry>
                <material name="gray" />
            </visual>
            <collision>
                <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
                <geometry>
                    <cylinder radius="${motor_radius}" length = "${motor_length}"/>
                </geometry>
            </collision>
            <cylinder_inertial_matrix  m="${motor_mass}" r="${motor_radius}" h="${motor_length}" />
        </link>

        <gazebo reference="${prefix}_motor_link">
            <material>Gazebo/Gray</material>
        </gazebo>

        <!-- Transmission is important to link the joints and the controller -->
        <transmission name="${prefix}_motor_joint_trans">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="${prefix}_motor_joint" >
                <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            </joint>
            <actuator name="${prefix}_motor_joint_motor">
                <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
                <mechanicalReduction>1</mechanicalReduction>
            </actuator>
        </transmission>
    </xacro:macro>

    <!-- Macro for robot wheel -->
    <xacro:macro name="wheel" params="prefix reflect">
        <joint name="${prefix}_wheel_joint" type="continuous">
            <origin xyz="0 ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0"/>
            <parent link="${prefix}_motor_link"/>
            <child link="${prefix}_wheel_link"/>
            <axis xyz="0 1 0"/>
        </joint>

        <link name="${prefix}_wheel_link">
            <visual>
                <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
                <geometry>
                    <cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
                </geometry>
                <material name="gray" />
            </visual>
            <collision>
                <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
                <geometry>
                    <cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
                </geometry>
            </collision>
            <cylinder_inertial_matrix  m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
        </link>

        <gazebo reference="${prefix}_wheel_link">
            <material>Gazebo/Gray</material>
        </gazebo>

        <!-- Transmission is important to link the joints and the controller -->
        <transmission name="${prefix}_wheel_joint_trans">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="${prefix}_wheel_joint" >
                <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            </joint>
            <actuator name="${prefix}_wheel_joint_motor">
                <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
                <mechanicalReduction>1</mechanicalReduction>
            </actuator>
        </transmission>
    </xacro:macro>

    <!-- Macro for robot caster -->
    <xacro:macro name="caster" params="prefix reflect">
        <joint name="${prefix}_caster_joint" type="continuous">
            <origin xyz="${caster_joint_x} 0 ${caster_joint_z+caster_link_z}" rpy="0 0 0"/>
            <parent link="base_link"/>
            <child link="${prefix}_caster_link"/>
            <axis xyz="0 1 0"/>
        </joint>

        <link name="${prefix}_caster_link">
            <visual>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <sphere radius="${caster_radius}" />
                </geometry>
                <material name="black" />
            </visual>
            <collision>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <sphere radius="${caster_radius}" />
                </geometry>
            </collision>      
            <sphere_inertial_matrix  m="${caster_mass}" r="${caster_radius}" />
        </link>

        <gazebo reference="${prefix}_caster_link">
            <material>Gazebo/Black</material>
        </gazebo>
    </xacro:macro>

    <!-- Macro for robot base-->
    <xacro:macro name="mybot_base_gazebo">
        <link name="base_footprint">
            <visual>
                <origin xyz="0 0 0" rpy="0 0 0" />
                <geometry>
                    <box size="0.001 0.001 0.001" />
                </geometry>
            </visual>
        </link>
        <gazebo reference="base_footprint">
            <turnGravityOff>false</turnGravityOff>
        </gazebo>

        <joint name="base_footprint_joint" type="fixed">
            <origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />        
            <parent link="base_footprint"/>
            <child link="base_link" />

以上是关于《ROS理论与实践》学习笔记构建机器人仿真平台的主要内容,如果未能解决你的问题,请参考以下文章

《ROS理论与实践》学习笔记机器视觉处理

《ROS理论与实践》学习笔记机器人自主导航

《ROS理论与实践》学习笔记机器人自主导航

《ROS理论与实践》学习笔记机器人SLAM建图

《ROS理论与实践》学习笔记机器人SLAM建图

《ROS理论与实践》学习笔记机器人语音交互