Ouster OS1-128 雷达调试

在这里记录一下自己使用 Ouster OS1-128 线雷达过程中踩过的一些坑。

一. 硬件连接

我这里使用的是 OS1-128线的雷达,长这个样子,实际尺寸挺小的,不到一个手掌大,比速腾/禾赛/velodyne的产品都要小。具体的可以去他们的官网看:Ouster官网

在这里插入图片描述
数据线的连接方式的话,和其他品牌的雷达基本一样,这里有个图,很清楚:
在这里插入图片描述
需要注意的是,因为这个雷达是美国的,所以自带的电源插头是美标的,需要买一个国标和美标的插头转换器,就 ok。

二. IP配置

首先我要吐槽一下,官网给的软件说明文档,是 GEN1 的,上一代产品的,我用的这个是 GEN2 的,所以有些不一样,需要下软件手册的话,可以从这里下:OS1 User Guide

说明里的 Networking Guide 部分有教怎么配置的,写的很详细 (换句话说就是很繁琐…) 说明了该怎么配置雷达和电脑的连接。 也是踩了挺多坑,总结了一下,比较简单的实现快速配置的几个步骤:

你可以把雷达连上电脑之后,ping一下试试,应该是可以ping通的:

ping -c1 os-992030000210.local

注意:这里就是 os 不是 os1 , 一个容易踩坑的地方,可能因为我这个是 GEN 2 代雷达的原因。然后就是别忘了加 .local, GEN 1 代产品的使用说明中,这个指令就没加 .local 这个后缀… 还有记得把雷达的序列号换成你自己的就ok。

如果你能ping 通的话,那么在浏览器里,应该也是可以看到雷达的信息的:

http://os-992030000210.local/

1. 修改电脑ip

sudo gedit /etc/network/interfaces

改成静态的ip

# interfaces(5) file used by ifup(8) and ifdown(8)
auto lo
iface lo inet loopback

# The primary network interface - use DHCP to find our address
# auto eth0
# iface eth0 inet dhcp

auto eth0
iface eth0 inet static
address 192.168.100.1
netmask 255.255.255.0
#gateway 192.168.190.2

注意:这里的 eth0 要根据自己的电脑修改,用 ifconfig 命令查看

然后重启网络:

sudo /etc/init.d/networking restart

建议输完,这个命令之后,重启一下电脑 (xuan xue && 常规操作)

额外:如何修改网卡的名称:

sudo gedit /etc/default/grub 
找到GRUB_CMDLINE_LINUX=""
改为GRUB_CMDLINE_LINUX="net.ifnames=0 biosdevname=0"
然后sudo grub-mkconfig -o /boot/grub/grub.cfg
重启后,网卡名称果然变成了eth0和wlan0

2. 分配雷达ip

这时候需要给,雷达分配一个 ip, 这个 ip 和刚刚自己设置的 ip 都是在一个子网下,软件手册中,关于设置写的很复杂,但其实就这么一句话就ok了:

sudo dnsmasq -C /dev/null -kd -F 192.168.100.50,192.168.100.200 -i eth0 --bind-dynamic

这里的 etho 要换成你自己的网卡名称!

意思就是在 192.168.100.50 到192.168.100.200 这么个区间内,随机分配一个地址,输入完,应该是这样的:

在这里插入图片描述
然后试着 ping 一下,也是可以 ping 通的,ok 那么大功就告成一半了。

三. ROS下显示点云

我又要吐槽一下,我一开始是按照官方的 Ouster-example GitHub说明安装配置的,然后没整出来…后来问了一下,和我说 GitHub, 上面的说明很久没有更新了…好的又成功踩坑…

还是在上面那个网站上,把新的固件下下来,然后:

1. 安装ROS驱动步骤

(1)进入ouster_example -> ouster_viz文件夹,打开README.md, 按照里面的Build Dependencies步骤完成对dependencies的安装;

(2) 进入ouster_example -> ouster_client文件夹,打开README.md, 按照里面的步骤buildclient;

(3)最后进入ouster_example -> ouster_ros文件夹,打开里面的打开README.md,按照里面的步骤完成build即可

应该就可以了,然后在 ouster_ros 这个文件夹里执行:

roslaunch ouster.launch sensor_hostname:=os-992030000210.local udp_dest:=192.168.100.1 lidar_mode:=2048x10 viz:=true

这里的 lidar_mode:=2048x10, 意思应该是水平2048个点,频率是10hz

注意:

  1. .local 后缀不要忘了
  2. 这里输入的 ip 地址是电脑的ip, 不是雷达的ip
  3. 特别提醒:在工作空间编译的时候,必须要按照 readme 里面的指令来, 不能只用 ‘catkin_make’, 还要加上编译选项 ‘Release’ 模式,这样显示出来的结果才没问题。

2. 显示效果

在这里插入图片描述
这么一看,点云还是很稠密的,不愧是128线

官方提供的数据也可以在这里下载:

ouster示例数据

四. 使用 LeGO-LOAM 建图

源码在这里:LeGO-LOAM
因为用的是 Ouster 128 雷达,所以有些地方需要修改一下:

  • 修改 utility.h 文件

修改其中订阅点云的 topic:

// extern const string pointCloudTopic = "/velodyne_points";
extern const string pointCloudTopic = "/os_cloud_node/points";

修改 useCloudRing 选项:改成 false

extern const bool useCloudRing = false; // if true, ang_res_y and ang_bottom are not used

不改的话会报错:

 Failed to find match for field 'ring'

修改雷达的参数

/*-------------------------------------------------
DJQ 2020-09-04
-------------------------------------------------*/
// Ouster OS1-128 (GEN 2)
extern const string LIDAR_TYPE = "Ouster OS1-128";
extern const int N_SCAN = 128;
extern const int Horizon_SCAN = 2048;
extern const float ang_res_x = 360.0/float(Horizon_SCAN);
extern const float ang_res_y = 45.0/float(N_SCAN-1);
extern const float ang_bottom = 22.5+0.1;
extern const int groundScanInd = 15;
  • 修改 imageProjection.cpp 文件

166 行需要把注释去掉:

cloudHeader.stamp = ros::Time::now(); // Ouster lidar users may need to uncomment this line

然后就正常编译,运行,就能跑 LeGO-LOAM 了。

五. TODO

  1. 这里有一个Ouster 雷达使用的讨论区,值得一看:

    Welcome to the GL forum for OUSTER lidar sensors!

  2. 看到开源的 LIO-SAM 框架,里面使用了 Ouster+ IMU,效果很好,可以之后试一试:

    LIO-SAM

  3. SC-LeGO-LOAM

以上就是Ouster雷达使用的步骤,觉得有用的可以随手点个赞 ~

  • 22
    点赞
  • 70
    收藏
    觉得还不错? 一键收藏
  • 22
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值