请大家完成之前的博客内容
1.ROS:新建xacro形式的模型,在rviz中显示模型(手把手!)
2.在自己的xacro模型的基础上加入常见传感器在rviz中显示
新建一个功能包myrobot_ga
因为我们已经手把手进行了之前的内容学习得到自己的myrobot功能包
那么我们可以直接进行复制粘贴的方式进行创建新的myrobot_ga功能包
1.复制粘贴myrobot功能包并重命名为myrobot_ga
2.对myrobot_ga的mainpage.dox,manifest.xml文件进行修改
修改mainpage.dox
修改mainfest.xml
3.设置myrobot_ga的环境路径
进入~(/home/xxx(用户名))目录下,找到.bashrc文件
打开并添加你的myrobot_ga的环境路径
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/nzh(自己修自己的工作空间位置)/src/myrobot_ga
注意哦!这里的nzh是你的工作空间文件夹名称!自己修改成自己的哦!
source ~/.bashrc
记得重新启动一下进而加载.bashrc文件
4.修改urdf文件中的robot1_base.xacro(基础机器人)
修改robot1_base.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
name="robot0">
<xacro:property name="length_wheel" value="0.05" />
<xacro:property name="radius_wheel" value="0.05" />
<xacro:property name="base_link_radius" value="0.1" />
<link name="base_footprint">
<visual>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</visual>
<collision>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
<mass value="0.0001"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<gazebo reference="base_footprint">
<material>Gazebo/Green</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
</link>
<link name="base_link">
<visual>
<geometry>
<box size="0.2 0.3 0.1"/>
</geometry>
<origin rpy="0 0 1.54" xyz="0 0 0.05"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2 0.3 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="10"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<gazebo reference="base_link">
<material>Gazebo/White</material>
</gazebo>
</link>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base_footprint"/>
</joint>
<link name="wheel_1">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<gazebo reference="wheel_1">
<material>Gazebo/Black</material>
</gazebo>
</link>
<link name="wheel_2">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<gazebo reference="wheel_2">
<material>Gazebo/Black</material>
</gazebo>
</link>
<link name="wheel_3">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<gazebo reference="wheel_3">
<material>Gazebo/Black</material>
</gazebo>
</link>
<link name="wheel_4">
<visual>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${length_wheel}" radius="${radius_wheel}"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<gazebo reference="wheel_4">
<material>Gazebo/Black</material>
</gazebo>
</link>
<!-- Joint definitions -->
<joint name="base_l_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_1"/>
<origin rpy="1.5707 0 0" xyz="0.1 0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="base_r_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_2"/>
<origin rpy="1.5707 0 0" xyz="-0.1 0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="base_wheel3_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_3"/>
<origin rpy="1.5707 0 0" xyz="0.1 -0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="base_wheel4_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_4"/>
<origin rpy="1.5707 0 0" xyz="-0.1 -0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
<!-- Gazebo Plugin -->
<gazebo>
<plugin name="arbotix_driver" filename="libarbotix_driver.so">
<rosparam file="$(find myrobot)/config/fake_mrobot_arbotix.yaml" command="load"/>
<param name="sim" value="true"/>
</plugin>
</gazebo>
<!-- Controller Plugin -->
<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>base_l_wheel_joint</leftJoint>
<rightJoint>base_r_wheel_joint</rightJoint>
<wheelSeparation>${base_link_radius * 2}</wheelSeparation>
<wheelDiameter>${2 * radius_wheel}</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>
</robot>
5.修改launch文件display_xacro.launch
修改display_xacro.launch
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find myrobot_ga)/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 myrobot_ga)/urdf/robot1_base.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 mrobot -param robot_description"/>
</launch>
注意:
1.这个display_xacro.launch是调用最基础的机器人模型的launch,在之前文章似乎有的使用的myrobot.launch文件,这里叫什么无所谓,核心是launch文件指向的模型文件路径正确
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find myrobot_ga)/urdf/robot1_base.xacro'" />
2.
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find myrobot_ga)/worlds/playground.world"/>
对于这行是对仿真进行添加一下障碍物(家具等其它模型来仿真一个特殊环境),如果想效果最大化的话
下载仿真使用的worlds文件
链接: https://pan.baidu.com/s/1H-PycN3KFIfTT_yUY0mI2A?pwd=1xh6 提取码: 1xh6
将worlds放到myrobot_gad功能包目录下
6.运行display_xacro.launch文件
roslaunch myrobot_ga display_xacro.launch
强烈建议使用流量进行连接,校园网的WiFi会比较慢
(鼠标滚轮拉进或远离,按住鼠标中键滚轮可以调整视角,左键可以平拉平面)
其它好玩的希望读者自己探索!
让我们看一下如何没有加worlds文件的效果
7.控制机器人进行移动
a.运行display_xacro.launch文件
roslaunch myrobot_ga display_xacro.launch
b.运行rostopic list
rostopic list
c.运行roslaunch mrobot_teleop mrobot_teleop.launch.
roslaunch mrobot_teleop mrobot_teleop.launch
小车成功运动!
在机器人上加入摄像头传感器进行仿真
1.修改camera.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="camera">
<xacro:macro name="usb_camera" params="prefix:=camera">
<!-- 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>
<box size="0.01 0.04 0.04" />
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.04 0.04" />
</geometry>
</collision>
</link>
<gazebo reference="${prefix}_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="${prefix}_link">
<sensor type="camera" name="camera_node">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>/camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
2.修改我们的mrobot_with_camera.urdf.xacro
<?xml version="1.0"?>
<robot name="mrobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find myrobot_ga)/urdf/robot1_base.xacro" />
<xacro:include filename="$(find myrobot_ga)/urdf/camera.xacro" />
<xacro:property name="camera_offset_x" value="0.1" />
<xacro:property name="camera_offset_y" value="0" />
<xacro:property name="camera_offset_z" value="0.2" />
<xacro:usb_camera prefix="camera"/>
<joint name="camera_joint" type="fixed">
<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
</robot>
核心修改地方:myrobot_ga
<xacro:include filename="$(find myrobot_ga)/urdf/robot1_base.xacro" />
<xacro:include filename="$(find myrobot_ga)/urdf/camera.xacro" />
3.修改xiangji.launch
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find myrobot_ga)/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 myrobot_ga)/urdf/mrobot_with_camera.urdf.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 mrobot -param robot_description"/>
</launch>
核心修改的地方就是模型位置
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find myrobot_ga)/urdf/mrobot_with_camera.urdf.xacro'" />
4.运行xiangji.launch
roslaunch myrobot_ga xiangji.launch
5.进行摄像头仿真
a. 运行rostopic list
rostopic list
b.运行rqt_image_view
rqt_image_view
摄像头仿真完毕!!!!
在机器人上加入Kinect仿真传感器进行仿真
1.修改kinect.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="kinect_camera">
<xacro:property name="M_PI" value="3.14159265358979323846"/>
<xacro:macro name="kinect_camera" params="prefix:=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://myrobot/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>
2.修改mrobot_with_kinect.urdf.xacro
<?xml version="1.0"?>
<robot name="mrobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find myrobot_ga)/urdf/robot1_base.xacro" />
<xacro:include filename="$(find myrobot_ga)/urdf/kinect.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.15" />
<mrobot_body/>
<xacro:kinect_camera prefix="kinect"/>
<joint name="kinect_frame_joint" type="fixed">
<origin xyz="${kinect_offset_x} ${kinect_offset_y} ${kinect_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="kinect_link"/>
</joint>
</robot>
3.修改deepxiangji.launch
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find myrobot_ga)/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 myrobot_ga)/urdf/mrobot_with_kinect.urdf.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 mrobot -param robot_description"/>
</launch>
4. 运行deepxiangji.launch并对深度相机进行仿真
a. 运行deepxiangji.launch
roslaunch myrobot deepxiangji.launch
b.运行
rostopic list
c.运行rosrun rviz rviz
rosrun rviz rviz
d.rviz的Fixed Frame设置为“Kinect_frame_optical”
e.后添加一个PointCloud2类型的插件,修改插件订阅的话题为/Kinect/depth/points,此时就可以在主界面中点云信息
深度相机仿真完成!!!!!
在机器人上加入雷达传感器进行仿真
1.修改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>
2.修改mrobot_with_rplidar.urdf.xacro
<?xml version="1.0"?>
<robot name="mrobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find myrobot_ga)/urdf/robot1_base.xacro" />
<xacro:include filename="$(find myrobot_ga)/urdf/rplidar.xacro" />
<xacro:property name="rplidar_offset_x" value="0" />
<xacro:property name="rplidar_offset_y" value="0" />
<xacro:property name="rplidar_offset_z" value="0.18" />
<mrobot_body/>
<xacro:rplidar prefix="laser"/>
<joint name="rplidar_joint" type="fixed">
<origin xyz="${rplidar_offset_x} ${rplidar_offset_y} ${rplidar_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="laser_link"/>
</joint>
</robot>
3.修改leida.launch
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find myrobot_ga)/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 myrobot_ga)/urdf/mrobot_with_rplidar.urdf.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 mrobot -param robot_description"/>
</launch>
4.运行leida.launch并仿真
a.运行roslaunch myrobot_ga leida.launch
roslaunch myrobot_ga leida.launch
b.运行rostopic list
rostopic list
c.运行rosrun rviz rviz
rosrun rviz rviz
d.设置rviz
在rviz中设置“Fixed Frame”为“base_link”,然后添加一个LaserScan类型的插件,修改插件订阅的话题为“/scan”,就可以看到界面中的激光数据了
!!!!雷达仿真实现!!!!