第六章 构建机器人仿真平台 课后作业

代码包

所有代码已上传至github网站:
github链接: https://github.com/YuemingBi/ros_practice/tree/master

课后作业

在这里插入图片描述

第一题

(1)view_robot_kinect_rplidar.launch

<launch>

    <!-- 设置launch文件的参数 -->
    <arg name="world_name" value="$(find robot_gazebo)/worlds/playground.world"/>
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>

    <!-- 运行gazebo仿真环境 -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="world_name" value="$(arg world_name)" />
        <arg name="debug" value="$(arg debug)" />
        <arg name="gui" value="$(arg gui)" />
        <arg name="paused" value="$(arg paused)"/>
        <arg name="use_sim_time" value="$(arg use_sim_time)"/>
        <arg name="headless" value="$(arg headless)"/>
    </include>

    <!-- 加载机器人模型描述参数 -->
    <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find robot_description)/urdf/robot_kinect_rplidar.xacro'" />

    <!-- 运行joint_state_publisher节点,发布机器人的关节状态  -->
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>

    <!-- 运行robot_state_publisher节点,发布tf  -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"  output="screen" >
        <param name="publish_frequency" type="double" value="50.0" />
    </node>

    <!-- 在gazebo中加载机器人模型-->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -model robot -param robot_description"/>

</launch>

(2)robot_kinect_rplidar.xacro

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

  <xacro:include filename="$(find robot_description)/urdf/robot_body.xacro" />
  <xacro:include filename="$(find robot_description)/urdf/sensor/kinect.xacro" />
  <xacro:include filename="$(find robot_description)/urdf/sensor/rplidar.xacro" />

  <xacro:property name="kinect_offset_x" value="-0.06" />
	<xacro:property name="kinect_offset_y" value="0" />
	<xacro:property name="kinect_offset_z" value="0.035" />

  <xacro:property name="rplidar_offset_x" value="0" />
	<xacro:property name="rplidar_offset_y" value="0" />
	<xacro:property name="rplidar_offset_z" value="0.028" />

  <robot_body/>

  <joint name="kinect_frame_joint" type="fixed">
		<origin xyz="${kinect_offset_x} ${kinect_offset_y} ${kinect_offset_z}" rpy="0 0 0" />
		<parent link="plate_2_link"/>
		<child link="camera_link"/>
	</joint>

	<xacro:kinect_camera prefix="camera"/>

  <joint name="rplidar_joint" type="fixed">
		<origin xyz="${rplidar_offset_x} ${rplidar_offset_y} ${rplidar_offset_z}" rpy="0 0 0" />
		<parent link="plate_1_link"/>
		<child link="laser_link"/>
	</joint>

	<xacro:rplidar prefix="laser"/>

</robot>

(3)robot_body.xacro

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

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

  <xacro:property name="motor_mass" value="1" />
  <xacro:property name="motor_radius" value="0.02" />
  <xacro:property name="motor_length" value="0.08" />
  <xacro:property name="motor_x" value="-0.055" />
  <xacro:property name="motor_y" value="0.075" />

  <xacro:property name="wheel_mass" value="2" />
  <xacro:property name="wheel_radius" value="0.033" />
  <xacro:property name="wheel_length" value="0.017" />
  <xacro:property name="wheel_y" value="${(motor_length+wheel_length)/2}" />

  <xacro:property name="plate_mass" value="2" />
  <xacro:property name="plate_radius" value="0.13" />
  <xacro:property name="plate_length" value="0.005" />
  <xacro:property name="plate_height" value="0.07" />

  <xacro:property name="standoff_x" value="0.12" />
  <xacro:property name="standoff_y" value="0.10" />

  <xacro:property name="caster_mass" value="0.5" />
  <xacro:property name="caster_radius" value="${wheel_radius/2}" />


  <!-- 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>
  <material name="white">
      <color rgba="1 1 1 0.9" />
  </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>
  <xacro:macro name="box_inertial_matrix">
      <inertial>
          <mass value="0.001" />
          <origin xyz="0 0 0" />
          <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
                   iyy="0.0001" iyz="0.0"
                   izz="0.0001" />
      </inertial>
  </xacro:macro>

  <!-- Macro for robot plate -->
  <xacro:macro name="plate" params="parent number x y z">
      <joint name="plate_${number}_joint" type="fixed">
          <origin xyz="${x} ${y} ${z}" rpy="0 0 0" />
          <parent link="${parent}" />
          <child link="plate_${number}_link" />
      </joint>

      <link name="plate_${number}_link">
          <visual>
              <origin xyz="0 0 0" rpy="0 0 0" />
              <geometry>
                  <cylinder radius="${plate_radius}" length="${plate_length}" />
              </geometry>
              <material name="yellow" />
          </visual>

          <collision>
              <origin xyz="0 0 0" rpy="0 0 0" />
              <geometry>
                  <cylinder radius="${plate_radius}" length="${plate_length}" />
              </geometry>
          </collision>
          <cylinder_inertial_matrix m="5" r="${plate_radius}" h="${plate_length}" />
      </link>

      <gazebo reference="plate_${number}_link">
            <material>Gazebo/Yellow</material>
      </gazebo>
  </xacro:macro>

  <!-- Macro for robot standoff -->
  <xacro:macro name="standoff" params="parent number x y z">
      <joint name="standoff_${number}_joint" type="fixed">
          <origin xyz="${x} ${y} ${z}" rpy="0 0 0" />
          <parent link="${parent}"/>
          <child link="standoff_${number}_link" />
      </joint>

      <link name="standoff_${number}_link">
          <visual>
              <origin xyz=" 0 0 0 " rpy="0 0 0" />
              <geometry>
                  <box size="0.01 0.01 0.07" />
              </geometry>
              <material name="black" />
          </visual>

          <collision>
              <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
              <geometry>
                  <box size="0.01 0.01 0.07" />
              </geometry>
          </collision>
          <box_inertial_matrix />
      </link>

      <gazebo reference="standoff_${number}_link">
          <material>Gazebo/Black</material>
      </gazebo>
  </xacro:macro>

  <!-- Macro for robot motor -->
  <xacro:macro name="motor" params="prefix reflect">
    <joint name="${prefix}_motor_joint" type="fixed">
        <origin xyz="${motor_x} ${reflect*motor_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/White</material>
    </gazebo>
  </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_y} 0" 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="white" />
          </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/White</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>

  <xacro:macro name="robot_body">
      <!-- base_footprint -->
      <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>

      <!-- base_link -->
      <joint name="base_footprint_joint" type="fixed">
        <origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
        <parent link="base_footprint"/>
        <child link="base_link"/>
      </joint>

      <link name="base_link">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${plate_radius}" length="${plate_length}" />
            </geometry>
            <material name="yellow" />
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder radius="${plate_radius}" length = "${plate_length}"/>
            </geometry>
        </collision>
        <cylinder_inertial_matrix  m="${plate_mass}" r="${plate_radius}" h="${plate_length}" />
    </link>
    <gazebo reference="base_link">
        <material>Gazebo/Yellow</material>
    </gazebo>

      <!-- plate -->
      <plate parent="base_link" number="1" x="0" y="0" z="${plate_height}" />
      <plate parent="plate_1_link" number="2" x="0" y="0" z="${plate_height}" />

      <!-- motor -->
      <motor prefix="left" reflect="1" />
      <motor prefix="right" reflect="-1" />

      <!-- wheel -->
      <wheel prefix="left" reflect="1" />
      <wheel prefix="right" reflect="-1" />

      <!-- standoff -->
      <standoff parent="base_link" number="1" x="-${standoff_x/2 + 0.03}" y="-${standoff_y - 0.03}" z="${plate_height/2}" />
      <standoff parent="base_link" number="2" x="-${standoff_x/2 + 0.03}" y="${standoff_y - 0.03}" z="${plate_height/2}" />
      <standoff parent="base_link" number="3" x="${standoff_x/2}" y="-${standoff_y}" z="${plate_height/2}" />
      <standoff parent="base_link" number="4" x="${standoff_x/2}" y="${standoff_y}" z="${plate_height/2}" />

      <standoff parent="plate_1_link" number="5" x="-${standoff_x/2 + 0.03}" y="-${standoff_y - 0.03}" z="${plate_height/2}" />
      <standoff parent="plate_1_link" number="6" x="-${standoff_x/2 + 0.03}" y="${standoff_y - 0.03}" z="${plate_height/2}" />
      <standoff parent="plate_1_link" number="7" x="${standoff_x/2}" y="-${standoff_y}" z="${plate_height/2}" />
      <standoff parent="plate_1_link" number="8" x="${standoff_x/2}" y="${standoff_y}" z="${plate_height/2}" />

      <!-- front_caster -->
      <joint name="front_caster_joint" type="continuous">
          <origin xyz="${plate_radius-wheel_radius/2} 0 -${wheel_radius/2}" rpy="0 0 0"/>
          <parent link="base_link"/>
          <child link="front_caster_link"/>
          <axis xyz="0 1 0"/>
      </joint>

      <link name="front_caster_link">
          <visual>
              <origin xyz="0 0 0" rpy="${M_PI/2} 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="front_caster_link">
          <material>Gazebo/Black</material>
      </gazebo>

      <!-- controller -->
      <gazebo>
          <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
              <rosDebugLevel>Debug</rosDebugLevel>
              <publishWheelTF>true</publishWheelTF>
              <robotNamespace>/</robotNamespace>
              <publishTf>1</publishTf>
              <publishWheelJointState>true</publishWheelJointState>
              <alwaysOn>true</alwaysOn>
              <updateRate>100.0</updateRate>
              <legacyMode>true</legacyMode>
              <leftJoint>left_wheel_joint</leftJoint>
              <rightJoint>right_wheel_joint</rightJoint>
              <wheelSeparation>${plate_radius*2}</wheelSeparation>
              <wheelDiameter>${2*wheel_radius}</wheelDiameter>
              <broadcastTF>1</broadcastTF>
              <wheelTorque>30</wheelTorque>
              <wheelAcceleration>1.8</wheelAcceleration>
              <commandTopic>cmd_vel</commandTopic>
              <odometryFrame>odom</odometryFrame>
              <odometryTopic>odom</odometryTopic>
              <robotBaseFrame>base_footprint</robotBaseFrame>
          </plugin>
      </gazebo>

  </xacro:macro>

</robot>

(4)kinect.xacro

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

    <xacro:macro name="kinect_camera" params="prefix:=camera">
        <!-- Create kinect reference frame -->
        <!-- Add mesh for kinect -->
        <link name="${prefix}_link">
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <visual>
                <origin xyz="0 0 0" rpy="0 0 ${M_PI/2}"/>
                <geometry>
                    <mesh filename="package://robot_description/meshes/kinect.dae" />
                </geometry>
            </visual>
            <collision>
                <geometry>
                    <box size="0.07 0.3 0.09"/>
                </geometry>
            </collision>
        </link>

        <joint name="${prefix}_optical_joint" type="fixed">
            <origin xyz="0 0 0" rpy="-1.5708 0 -1.5708"/>
            <parent link="${prefix}_link"/>
            <child link="${prefix}_frame_optical"/>
        </joint>

        <link name="${prefix}_frame_optical"/>

        <gazebo reference="${prefix}_link">
            <sensor type="depth" name="${prefix}">
                <always_on>true</always_on>
                <update_rate>20.0</update_rate>
                <camera>
                    <horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
                    <image>
                        <format>R8G8B8</format>
                        <width>640</width>
                        <height>480</height>
                    </image>
                    <clip>
                        <near>0.05</near>
                        <far>8.0</far>
                    </clip>
                </camera>
                <plugin name="kinect_${prefix}_controller" filename="libgazebo_ros_openni_kinect.so">
                    <cameraName>${prefix}</cameraName>
                    <alwaysOn>true</alwaysOn>
                    <updateRate>10</updateRate>
                    <imageTopicName>rgb/image_raw</imageTopicName>
                    <depthImageTopicName>depth/image_raw</depthImageTopicName>
                    <pointCloudTopicName>depth/points</pointCloudTopicName>
                    <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
                    <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
                    <frameName>${prefix}_frame_optical</frameName>
                    <baseline>0.1</baseline>
                    <distortion_k1>0.0</distortion_k1>
                    <distortion_k2>0.0</distortion_k2>
                    <distortion_k3>0.0</distortion_k3>
                    <distortion_t1>0.0</distortion_t1>
                    <distortion_t2>0.0</distortion_t2>
                    <pointCloudCutoff>0.4</pointCloudCutoff>
                </plugin>
            </sensor>
        </gazebo>

    </xacro:macro>
</robot>

(5)rplidar.xacro

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

    <xacro:macro name="rplidar" params="prefix:=laser">
        <!-- Create laser reference frame -->
        <link name="${prefix}_link">
            <inertial>
                <mass value="0.1" />
                <origin xyz="0 0 0" />
                <inertia ixx="0.01" ixy="0.0" ixz="0.0"
                         iyy="0.01" iyz="0.0"
                         izz="0.01" />
            </inertial>

            <visual>
                <origin xyz=" 0 0 0 " rpy="0 0 0" />
                <geometry>
                    <cylinder length="0.05" radius="0.05"/>
                </geometry>
                <material name="black"/>
            </visual>

            <collision>
                <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
                <geometry>
                    <cylinder length="0.06" radius="0.05"/>
                </geometry>
            </collision>
        </link>
        <gazebo reference="${prefix}_link">
            <material>Gazebo/Black</material>
        </gazebo>

        <gazebo reference="${prefix}_link">
            <sensor type="ray" name="rplidar">
                <pose>0 0 0 0 0 0</pose>
                <visualize>false</visualize>
                <update_rate>5.5</update_rate>
                <ray>
                    <scan>
                      <horizontal>
                        <samples>360</samples>
                        <resolution>1</resolution>
                        <min_angle>-3</min_angle>
                        <max_angle>3</max_angle>
                      </horizontal>
                    </scan>
                    <range>
                      <min>0.10</min>
                      <max>6.0</max>
                      <resolution>0.01</resolution>
                    </range>
                    <noise>
                      <type>gaussian</type>
                      <mean>0.0</mean>
                      <stddev>0.01</stddev>
                    </noise>
                </ray>
                <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
                    <topicName>/scan</topicName>
                    <frameName>laser_link</frameName>
                </plugin>
            </sensor>
        </gazebo>

    </xacro:macro>
</robot>

(6)运行结果

$ roslaunch robot_gazebo view_robot_kinect_rplidar.launch
$ roslaunch robot_teleop robot_teleop.launch (键盘控制机器人移动)

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

第二题

(1)robot_rviz.launch

<launch>

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

</launch>

(2)运行结果

$ roslaunch robot_gazebo view_robot_kinect_rplidar.launch
$ roslaunch robot_gazebo robot_rviz.launch
$ roslaunch robot_teleop robot_teleop.launch

在这里插入图片描述
rviz中左下角为kinect相机的彩色图像,图中的红线为rplidar激光雷达的信息。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

*昨夜星辰*

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值