群组信息 私有

administrators

  • 二维码摄像头和里程计的时间戳同步

    假设里程计时间戳和二维码摄像头的时间戳都是准确的(或者和真实时间都差了一个相同的固定值),那么同一时刻通过里程计计算的机器人移动的相对位姿应该和通过二维码计算的相对位资完全一样。因为两个传感器数据同一时刻对应的是同一个机器人位置。

    对于时间戳其真实值实际上对我们没有多大意义,更有意义的是不同传感器之间时间戳的偏差。通过这种方式我们可以用来校准这两个传感器的时间戳。我们可以以一个传感器的时间戳作为基准,其他传感器的时间戳对其到这个时间戳上。里程计时间戳就是一个很好的基准。

    我们控制机器人下方扫码摄像头在机器人正中央,保证机器人在原地旋转时二维码始终在自己的摄像头范围中央。同时录制摄像头和里程计数据。通过里程计数据可以计算出一个相对于初始位置的相对位姿,通过二维码数据也可以计算出一个相对位姿。机器人以固定速度原地旋转。很容易计算出这两个位姿的差就是 delta_theta = delta_t * w, 其中delta_t就是两个传感器的时间戳差别,w是机器人旋转的角速度。如果时间戳的差距是固定的,那么就应该有这个角度差也是固定的。

    通过实验我计算出 角度差均值是 -0.09949351795361913, 标准差是 0.014604546858801595
    可以看到这两个传感器的时间戳基本上确实是一个定值。机器人角速度为2rad/s,则计算出时间戳大概差50ms。把这个偏差加入到计算中相关精度有了明显的提升。

    发布在 技术交流
  • RE: 雷达数据的运动校准和里程计时间同步

    @weijiz 还有一点,如果不进行运动校准,直接在odom坐标系下看scan数据,你会发现之前存在的运动校准误差消失了。这是因为rviz在odom下显示scan数据的时候不是按照整体显示的,它会计算每个点的时间戳去显示。相当于完成了运动校准。所以如果你的运动校准计算正确,那么你的计算数据在odom下就应该和rviz的原始数据重合。

    发布在 激光雷达
  • 雷达数据的运动校准和里程计时间同步

    雷达固定在机器人上,当机器人运动时由于LaserScan每个beam存在时间差就会产生运动误差。同时如果里程计和雷达本身存在时间差,也会造成扫描误差。不过这两个误差的表现形式有所区别。

    首先是雷达的运动误差。如果在rviz中laser坐标系下看雷达数据。当机器人在原地快速旋转时,会发现雷达的x轴左右两边的数据是明显不一致的。如下图所示

    933d0dee-ff78-43e5-8230-5aa2317dd3d0-image.png

    右前方基本是两条平行线,当这个部分运动到雷达正前方时会发生形变

    e45b0e6f-b793-4be2-bc0e-211e139ade16-image.png

    两条直线不再平行。这是由于x轴两边的数据正好对应差了一个scan time。雷达产生的相对移动是最大的。

    通过计算实际时间差可以把这个修正回来。

    d4ee2e76-a8d9-444b-bd20-469ef8ab22a4-image.png
    图中红色就是修正后的数据。

    另一个主要的误差来自odom和scan的时间戳不同步。它会造成的误差表现是如果机器人在原地匀速旋转那么雷达数据和里程计当前对应的雷达数据就会差一个固定角度。如下图所示。

    7f115011-9515-4384-86b8-d20c2241a2ed-image.png

    其中绿色是真值红色是测量值。同时这个角度也很容易算出是delta_t * w, 其中delta_t是时间戳差值,w是旋转角速度。

    所以我们很容易通过现象去判断是否存在此误差。如果机器人原地旋转时在rviz中,odom坐标系下,你发现雷达数据随着角速度的不同有明显的整体的角度变化。那就说明存在一个雷达和里程计的时间戳是不同步的,有可能某个传感器的时间戳不准。

    发布在 激光雷达
  • RE: rk3588在ros中使用ros_rknn_yolo包

    @natsukirk3588在ros中使用ros_rknn_yolo包 中说:

    ros_rknn_yolo文件夹内有没有正确创建venv子文件夹,检查venv内的python虚拟环境是否正确创建了。
    同时可以手动按行执行一下rknn_yolo_node.sh这个bash文件中的指令内容,看是哪一行出了问题。

    发布在 技术交流
  • rk3588使用bw_rtsp_client包将rtsp视频流转成ros图像话题数据流

    《rk3588在ros中使用ros_rknn_yolo包》这篇文章中的图像话题来源,除了usb摄像头外,一般是监控摄像头。监控摄像头推的基本都是rtsp流,因此需要一个ros包来将rtsp视频流解码转换成ros图像话题数据流。使用bw_rtsp_client包,可以方便、高效率地在rk3588中完成这个任务,转换1080p的rtsp流延时低于160毫秒,cpu占用率单核小于50%。

    1. 下载与编译

    环境准备

    确保您的RK3588设备已经安装了ROS环境。本教程默认您使用的是ROS1版本,具体的安装步骤请参考ros_rknn_yolo包内的readme文件。
    rk3588的ubuntu系统还需要升降安装下列硬件解码库。

    https://git.bwbot.org/publish/librga
    https://git.bwbot.org/publish/mpp
    https://git.bwbot.org/publish/ffmpeg-rockchip
    https://git.bwbot.org/publish/rockchip_mirrors
    每个仓库readme里面有安装步骤
    

    克隆软件包

    首先,切换到您的ROS工作空间src目录下,然后克隆bw_rtsp_client软件包:

    cd ~/rk3588_ros_ws/src
    git clone https://git.bwbot.org/publish/bw_rtsp_client.git
    

    编译软件包

    返回到工作空间的根目录,进行编译:

    #开始编译
    cd ~/rk3588_ros_ws/
    catkin_make
    

    2. 启动Launch文件

    先找到一个rtsp数据流,可以用这个软件包《gst-rtsp-server》发布一个测试用的数据流。

     ./test-launch "( videotestsrc ! video/x-raw,width=1920,height=1080,framerate=30/1 ! timeoverlay ! tee name=vsrc vsrc. ! queue ! videoconvert ! ximagesink vsrc. ! queue ! mpph264enc tune=zerolatency ! rtph264pay name=pay0 pt=96 )"
    

    bw_rtsp_client包提供了Launch文件来启动节点和相关的配置。在另一个新开的终端中运行以下命令以启动:

    #将test.yaml文件中的rtsp_uri参数改成自己要订阅的rtsp流链接,再执行下列指令。
    roslaunch bw_rtsp_client test.launch
    

    在另一个新开的终端中使用image_view查看转换发布的话题

    rosrun image_view image_view
    

    屏幕截图 2024-09-03 115203.png

    3. 其它使用方式和参数

    请阅读bw_rtsp_client中的readme.md文件,可以使用service接口控制转换过程的开启和关闭。

    发布在 技术交流
  • RE: 小强ROS机器人教程(27)___bw_auto_dock自动充电功能包的使用和实现原理

    @xiaowei 没有就对应安装上 sudo apt install libboost-filesystem-dev

    发布在 产品服务
  • RE: 小强ROS机器人教程(27)___bw_auto_dock自动充电功能包的使用和实现原理

    @xiaowei 你的系统什么版本 默认boost应该是1.71.0的

    发布在 产品服务
  • RE: 小强ROS机器人教程(27)___bw_auto_dock自动充电功能包的使用和实现原理

    @xiaowei 执行上面的指令

    git clone http://git.bwbot.org/publish/bw_auto_dock.git
    cd bw_auto_dock
    git checkout noetic-version2
    

    如果不明白先学习一下git指令的使用

    发布在 产品服务
  • RE: 小强ROS机器人教程(27)___bw_auto_dock自动充电功能包的使用和实现原理

    @xiaowei 你切换到了noetic-version2 版本了吗 从代码看应该是没有

    发布在 产品服务
  • RE: 小强ROS机器人教程(27)___bw_auto_dock自动充电功能包的使用和实现原理

    @xiaowei 发一下你的错误

    发布在 产品服务