文章目录
- 一.确定雷达的型号
 - 二.安装驱动
 - 1.新建一个工作空间"lidar_ws"(随便一个你存放代码的地方)
 - 2.clone下驱动的源代码(在lidar_ws/src目录下)
 - 3.尝试编译一下(在lidar_ws目录下)
 
- 四.在RVIZ中的显示
 - 1.配置好IP地址
 - (1)雷达端:
 - (2)本机电脑端:
 
- 2.尝试运行“sdkeli_ls1207de_udp_with_1_lidars.launch”
 - 3.再次运行 sdkeli_ls1207de_udp_with_1_lidars.launch
 
- 五.利用hector算法扫个图
 - 1.安装hector包
 - 2.新建一个“hector_slam.launch”文件
 - 3.更改“sdkeli_ls1207de_udp_with_1_lidars.launch”文件
 - 4.更改xacro文件:sdkeli_ls_udp.urdf.xacro
 
一.确定雷达的型号
科力keli LSE型激光雷达 LSE-2027DE/H03
 

官网:http://www.sdkeli.com/cpzx/jgld/437.html
二.安装驱动
确切说不是安装驱动,这只是调用的底层代码。
 https://gitee.com/reinovo/sdkeli_ls_udp/tree/master
1.新建一个工作空间"lidar_ws"(随便一个你存放代码的地方)
mkdir -p lidar_ws/src
 
2.clone下驱动的源代码(在lidar_ws/src目录下)
git clone https://gitee.com/reinovo/sdkeli_ls_udp.git
 
3.尝试编译一下(在lidar_ws目录下)
catkin_make
 
出现下面的界面说明编译成功
 
四.在RVIZ中的显示
1.配置好IP地址
(1)雷达端:
确定雷达的IP地址,可以在Windows里通过官方提供的软件里查看
 我这里雷达的IP为:192.168.0.10
 在“sdkeli_ls1207de_udp_with_1_lidars.launch”文件下
 
(2)本机电脑端:
打开右上角的有线连接(此时已经把雷达的网线接到电脑的网口)
 
 打开设置
 
 
2.尝试运行“sdkeli_ls1207de_udp_with_1_lidars.launch”
source ./devel/setup.bash
roslaunch sdkeli_ls_udp sdkeli_ls1207de_udp_with_1_lidars.launch
 
报错如下:
 原因:之前版本xacro的引用写法和现状的写法不一样。
 参考:https://blog.csdn.net/weixin_45824920/article/details/122905005
 修改处:
<param name="robot_description" command="$(find xacro)/xacro.py '$(find sdkeli_ls_udp)/urdf/sdkeli_ls1207de.urdf.xacro'" />
 
更改为:
<param name="robot_description" command="$(find xacro)/xacro -i '$(find sdkeli_ls_udp)/urdf/sdkeli_ls1207de.urdf.xacro'" />
 

3.再次运行 sdkeli_ls1207de_udp_with_1_lidars.launch
source ./devel/setup.bash
roslaunch sdkeli_ls_udp sdkeli_ls1207de_udp_with_1_lidars.launch
 
还是报错,感觉还是语法的问题,之前版本的语法与现状版本的语法有出入。
 参考:https://blog.csdn.net/weixin_44525754/article/details/113773085
 修改处:
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
 
修改为:
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
 

五.利用hector算法扫个图
1.安装hector包
(noetic换成你ros版本)
sudo apt-get install ros-noetic-hector-slam
 
2.新建一个“hector_slam.launch”文件
<launch>
<!-- 
================================================================================
    这是启动 hecto扫图的程序入口,启动这个就行。
===============================================================================
 -->
<!-- 启动模型和rviz  这里配置好自己的rviz文件-->
  <include file="$(find sdkeli_ls_udp)/launch/lidar.launch"></include>
<node pkg = "hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
 <!-- Frame names -->
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map" />
<param name="base_frame" value="base_link" />
<param name="odom_frame" value="base_link" />
<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<!-- <!—— Map size / start point ——> -->
<param name="map_resolution" value="0.05"/>
<param name="map_size" value="2048"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />
<param name="map_multi_res_levels" value="2" />
<param name="map_pub_period" value="2" />
<param name="laser_min_dist" value="0.4" />
<param name="laser_max_dist" value="5.5" />
<param name="output_timing" value="false" />
<param name="pub_map_scanmatch_transform" value="true" />
<!-- <!—— Map update parameters ——> -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" /> 
<param name="map_update_distance_thresh" value="0.2"/>
<param name="map_update_angle_thresh" value="0.06" />
<!-- <!—— Advertising config ——>  -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="5"/>
<!-- 这里配置自己雷达发布的节点 -->
<param name="scan_topic" value="/keli_scan"/> 
</node>
</launch>
 
3.更改“sdkeli_ls1207de_udp_with_1_lidars.launch”文件
更改的地方如下:
 
“sdkeli_ls1207de_udp_with_1_lidars.launch”完整的代码如下:
<?xml version="1.0"?>
<launch>
  <!-- 创建模型 和发布 tf关系 -->
  <param name="robot_description" command="$(find xacro)/xacro -i  '$(find sdkeli_ls_udp)/urdf/sdkeli_ls1207de.urdf.xacro'" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
  <!-- 发布雷达数据 -->
  <node name="sdkeli_ls1207de" pkg="sdkeli_ls_udp" type="sdkeli_ls1207de" respawn="true" output="screen">
    <!--
      <param name="min_ang" type="double" value="-2.35619449019" />
      <param name="max_ang" type="double" value="2.35619449019" />
      <param name="intensity" type="bool" value="True" />
      <param name="skip" type="int" value="0" />
      <param name="frame_id" type="str" value="laser" />
      <param name="time_offset" type="double" value="-0.001" />
      <param name="publish_datagram" type="bool" value="False" />
      <param name="subscribe_datagram" type="bool" value="false" />
      <param name="device_number" type="int" value="0" />
      <param name="time_increment" type="double" value="0.000061722" />
      <param name="range_min" type="double" value="0.05" />
      <param name="range_max" type="double" value="10.0" />
    -->
      <remap from="scan" to="keli_scan" />
      <param name="frame_id" type="str" value="laser" />
      <param name="range_min" type="double" value="0.01" />
      <param name="range_max" type="double" value="30.0" />
      <param name="hostname" type="string" value="192.168.0.10" />
      <param name="port" type="string" value="2112" />
      <param name="timelimit" type="int" value="5" />
      <param name="checkframe" type="bool" value="true" />
  </node>
  <!-- 启动RVIZ 这里改成自己 .rviz-->
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find sdkeli_ls_udp)/rviz/scan_map.rviz"/>
</launch>
 
4.更改xacro文件:sdkeli_ls_udp.urdf.xacro
由于hector建图需要base_link坐标下,于是在该xacro文里添加base_link文件,(其实配置hector.launch文件里的坐标系该为雷达的坐标系也可以。)
添加下面代码:
 
 “sdkeli_ls_udp.urdf.xacro”完整的代码如下:
<?xml version="1.0"?>
<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
  xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
  xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
  xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="sdkeli_ls1207de" params="name ros_topic">
    <xacro:sdkeli_ls_udp name="${name}" ros_topic="${ros_topic}" 
      length="0.06" width="0.06" height="0.086" mass="0.250" z_offset="0.06296"
      min_range="0.01" max_range="100.0"
      mesh="package://sdkeli_ls_udp/meshes/sdkeli_ls1207de.stl" />
  </xacro:macro>
  <xacro:macro name="sdkeli_ls_udp" params="name ros_topic length width height mass z_offset min_range max_range mesh">
    <!-- z_offset: distance between base plate and laser center (= center of mesh) -->
    <link name="${name}_mount_link">
      <inertial>
        <mass value="0.001" />
        <origin xyz="0 0 0" />
        <inertia ixx="0.000001" ixy="0.0" ixz="0.0"
          iyy="0.000001" iyz="0.0" izz="0.000001" />
      </inertial>
    </link>
    <joint name="${name}_joint" type="fixed">
      <parent link="${name}_mount_link" />
      <child link="${name}" />
      <origin rpy="0 0 0" xyz="0 0 ${z_offset}"/>
    </joint>
    <link name="base_link">
    </link>
    <joint name="base_link_joint" type="fixed">
      <parent link="base_link" />
      <child link="${name}_mount_link" />
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </joint>
    <link name="${name}">
      <visual>
        <geometry>
          <mesh filename="${mesh}" />
        </geometry>
        <material name="blue" >
          <color rgba="0 0 1 1" />
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="${mesh}" />
        </geometry>
      </collision>
      <inertial>
        <mass value="${mass}" />
        <origin xyz="0 0 -0.026" />
        <inertia ixx="${0.0833333 * mass * (width * width + height * height)}" ixy="0.0" ixz="0.0"
          iyy="${0.0833333 * mass * (length * length + height * height)}" iyz="0.0"
          izz="${0.0833333 * mass * (length * length + width * width)}" />
      </inertial>
    </link>
    <xacro:sdkeli_ls_laser_gazebo_v0 name="${name}" link="${name}" ros_topic="${ros_topic}" update_rate="15.0" min_angle="-2.357" max_angle="2.357" min_range="${min_range}" max_range="${max_range}"/>
  </xacro:macro>
  <xacro:macro name="sdkeli_ls_laser_gazebo_v0" params="name link ros_topic update_rate min_angle max_angle min_range max_range">
    <gazebo reference="${link}">
      <material value="Gazebo/Blue" />
      <sensor type="ray" name="${name}">
        <always_on>true</always_on>
        <update_rate>${update_rate}</update_rate>
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <ray>
          <scan>
            <horizontal>
              <samples>271</samples>
              <resolution>1</resolution>
              <min_angle>${min_angle}</min_angle>
              <max_angle>${max_angle}</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>${min_range}</min>
            <max>${max_range}</max>
            <resolution>0.01</resolution>
          </range>
        </ray>
        <plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_laser.so">
          <gaussianNoise>0.005</gaussianNoise>
          <alwaysOn>true</alwaysOn>
          <updateRate>${update_rate}</updateRate>
          <topicName>${ros_topic}</topicName>
          <frameName>${link}</frameName>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>
</robot>
                


















