鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    ROS2 foxy cartographer纯激光建图报错

    已定时 已固定 已锁定 已移动 未解决
    动手学ROS2
    ros2-foxy cartographer建图 建图前的准备
    3
    5
    414
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • Y
      yu
      最后由 yu 编辑

      用的系统是ubuntu20.04,ros2版本是foxy,我现在想要用cartographer进行纯激光建图
      所用雷达的话题由卖家自动发布为utlidar/cloud_deskewed,坐标系为odom,详见附图,配置文件和代码如下:

      --这是lua配置文件
      include "map_builder.lua"
      include "trajectory_builder.lua"
      
      options = {
        map_builder = MAP_BUILDER,
        trajectory_builder = TRAJECTORY_BUILDER,
        map_frame = "map",
        tracking_frame = "odom",
        -- base_link改为odom,发布map到odom之间的位姿态
        published_frame = "base_link",   --**换成odom/map也试过**
        odom_frame = "odom",
        -- true改为false,不用提供里程计数据
        provide_odom_frame = false,
        -- false改为true,仅发布2D位资
        publish_frame_projected_to_2d = true,
        -- false改为true,使用里程计数据
        use_odometry = false,
        use_nav_sat = false,
        use_landmarks = false,
        -- 0改为1,使用一个雷达
        num_laser_scans = 1,
        -- 1改为0,不使用多波雷达
        num_multi_echo_laser_scans = 0,
        -- 10改为1,1/1=1等于不分割
        num_subdivisions_per_laser_scan = 1,
        num_point_clouds = 0,
        lookup_transform_timeout_sec = 0.2,
        submap_publish_period_sec = 0.3,
        pose_publish_period_sec = 5e-3,
        trajectory_publish_period_sec = 30e-3,
        rangefinder_sampling_ratio = 1.,
        odometry_sampling_ratio = 1.,
        fixed_frame_pose_sampling_ratio = 1.,
        imu_sampling_ratio = 1.,
        landmarks_sampling_ratio = 1.,
      }
      
      
      -- false改为true,启动2D SLAM
      MAP_BUILDER.use_trajectory_builder_2d = true
      
      -- TRAJECTORY_BUILDER_2D.scan_topic = '/utlidar/cloud_deskewed'
      
      -- 0改成0.10,比机器人半径小的都忽略
      TRAJECTORY_BUILDER_2D.min_range = 0.10
      -- 30改成3.5,限制在雷达最大扫描范围内,越小一般越精确些
      TRAJECTORY_BUILDER_2D.max_range = 5.0
      -- 5改成3,传感器数据超出有效范围最大值
      TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3.
      -- true改成false,不使用IMU数据,大家可以开启,然后对比下效果
      TRAJECTORY_BUILDER_2D.use_imu_data = false
      -- false改成true,使用实时回环检测来进行前端的扫描匹配
      TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true 
      -- 1.0改成0.1,提高对运动的敏感度
      TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)
      
      -- 0.55改成0.65,Fast csm的最低分数,高于此分数才进行优化。
      POSE_GRAPH.constraint_builder.min_score = 0.65
      --0.6改成0.7,全局定位最小分数,低于此分数则认为目前全局定位不准确
      POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
      
      TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
      TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
      TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
      POSE_GRAPH.optimization_problem.huber_scale = 1e2
      POSE_GRAPH.optimize_every_n_nodes = 35
      
      -- 设置0可关闭全局SLAM
      -- POSE_GRAPH.optimize_every_n_nodes = 0
      
      return options
      
      
      --这是节点启动的文件
      import os
      from launch import LaunchDescription
      from launch.substitutions import LaunchConfiguration
      from launch_ros.actions import Node
      from launch_ros.substitutions import FindPackageShare
      
      def generate_launch_description():
          # 定位到功能包的地址
          pkg_share = FindPackageShare(package='dog_map').find('dog_map')
          
          #=====================运行节点需要的配置=======================================================================
          # 是否使用仿真时间,我们用gazebo,这里设置成true
          use_sim_time = LaunchConfiguration('use_sim_time', default='false')
          # 地图的分辨率
          resolution = LaunchConfiguration('resolution', default='0.05')
      
          # frame_id = LaunchConfiguration('frame_id', default='odom')
          # 地图的发布周期
          publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0')
          # 配置文件夹路径
          configuration_directory = LaunchConfiguration('configuration_directory', default=os.path.join(pkg_share, 'config'))
          # 配置文件
          configuration_basename = LaunchConfiguration('configuration_basename', default='test_dog_2d.lua')
      
          #=====================声明三个节点,cartographer/occupancy_grid_node/rviz_node=================================
          cartographer_node = Node(
              package='cartographer_ros',
              executable='cartographer_node',
              name='cartographer_node',
              output='screen',
              parameters=[{'use_sim_time': use_sim_time}],
              arguments=['-configuration_directory', configuration_directory,
                         '-configuration_basename', configuration_basename],
              remappings = [('/scan','/utlidar/cloud_deskewed')]
              )  # 修改此处以正确映射话题
      
          occupancy_grid_node = Node(
              package='cartographer_ros',
              executable='occupancy_grid_node',
              name='occupancy_grid_node',
              output='screen',
              parameters=[{'use_sim_time': use_sim_time}],
              arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec])
      
          rviz_node = Node(
              package='rviz2',
              executable='rviz2',
              name='rviz2',
              # arguments=['-d', rviz_config_dir],
              parameters=[{'use_sim_time': use_sim_time}],
              output='screen')
      
          #===============================================定义启动文件========================================================
          ld = LaunchDescription()
          ld.add_action(cartographer_node)
          ld.add_action(occupancy_grid_node)
          ld.add_action(rviz_node)
      
          return ld
      
      

      遇到的问题:
      [rviz2-3] [INFO] [1723599876.257288727] [rviz2]: Stereo is NOT SUPPORTED
      [rviz2-3] [INFO] [1723599876.257418670] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
      [rviz2-3] [INFO] [1723599876.282416643] [rviz2]: Stereo is NOT SUPPORTED
      [occupancy_grid_node-2] [WARN] [1723599876.675592666] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [occupancy_grid_node-2] [WARN] [1723599877.675623726] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [occupancy_grid_node-2] [WARN] [1723599878.675600745] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [occupancy_grid_node-2] [WARN] [1723599879.675673102] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [occupancy_grid_node-2] [WARN] [1723599880.675637417] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [occupancy_grid_node-2] [WARN] [1723599881.675718859] [occupancy_grid_node]: submap_slices and last_frame_id is empty
      [rviz2-3] [WARN] [1723599882.177420468] [rviz2]: topic '/utlidar/cloud_deskewed' has more than one types associated, rviz will arbitrarily use the type 'sensor_msgs/msg/LaserScan' -- all types for the topic: 'sensor_msgs/msg/LaserScan' 'sensor_msgs/msg/PointCloud2'
      [occupancy_grid_node-2] [WARN] [1723599882.675668892] [occupancy_grid_node]: submap_slices and last_frame_id is empty

      没有生成TF树
      tf.png
      rqt_graph输出为:
      rqt_graph.png

      雷达话题和坐标系:
      lidar话题和坐标系.png
      huatidata.png

      报错:
      报错.png

      求各位大神救救孩子吧

      小鱼小 1 条回复 最后回复 回复 引用 0
      • 小伊小
        机器人小伊
        最后由 编辑

        从你提供的日志和配置来看,存在几个潜在的问题和解决方案,我们可以逐一排查和解决:

        1. occupancy_grid_node 的警告

        这个警告表明 occupancy_grid_node 没有接收到来自 cartographer_node 的任何子图(submap)数据。这通常是因为 cartographer_node 没有正确运行或者没有生成任何数据。

        解决方案:

        • 确保 cartographer_node 正在运行并且没有崩溃。
        • 检查 cartographer_node 的输出日志,看是否有更详细的错误信息。
        • 确保 cartographer_node 的配置文件中指定的激光话题 /utlidar/cloud_deskewed 是正确的,并且该话题确实在发布数据。

        2. RViz 的警告

        RViz 警告指出 /utlidar/cloud_deskewed 话题有两种消息类型(sensor_msgs/msg/LaserScan 和 sensor_msgs/msg/PointCloud2),这通常不是 cartographer 所期望的。cartographer 通常期望的是 sensor_msgs/msg/LaserScan。

        解决方案:

        • 确认 /utlidar/cloud_deskewed 话题是否应该发布 PointCloud2 或 LaserScan。如果应该发布 LaserScan,检查雷达的配置或驱动设置。
        • 如果雷达只能发布 PointCloud2,你可能需要编写一个转换节点将 PointCloud2 转换为 LaserScan。

        3. TF 树的缺失

        没有生成 TF 树可能是因为 cartographer_node 没有运行,或者没有正确发布 TF 变换。

        解决方案:

        • 确保 cartographer_node 的 published_frame 参数设置为正确的坐标系,通常是 map。
        • 检查 cartographer_node 是否在日志中输出了关于 TF 的任何错误。
        • 使用 ros2 tf2_echo 命令检查 TF 变换是否存在。

        4. 配置文件中的小错误

        你的配置文件中 published_frame = "base_kink" 可能是个打字错误,通常应该是 base_link 或其他机器人基座的坐标系,但在这个场景下应该是 map。

        解决方案:

        • 将 published_frame = "base_kink" 改为 published_frame = "map"。

        5. 雷达话题的订阅

        确保 cartographer_node 正确订阅了 /utlidar/cloud_deskewed 话题。从你的启动文件中看,你已经做了重映射,但确认一下雷达是否确实在这个话题上发布了数据。

        6. 检查 ROS 2 的包和环境

        • 确保所有 ROS 2 包都已正确安装,包括 cartographer_ros 和相关的依赖。
        • 重新启动 ROS 2 环境,确保所有服务都正确启动。

        通过以上步骤,你应该能够诊断并解决你遇到的问题。如果问题仍然存在,可能需要更详细地检查 cartographer_node 的日志输出,或者考虑在 ROS 2 社区或相关论坛中寻求帮助。


        以上为生成回答,仅供参考~

        我是小伊,已接入ChatGpt,所有回复,仅供参考~

        1 条回复 最后回复 回复 引用 0
        • Y yu 将这个主题转为问答主题,在
        • 小鱼小
          小鱼 技术大佬 @yu
          最后由 编辑

          @yu 在 ROS2 foxy cartographer纯激光建图报错 中说:

          rviz2]: topic '/utlidar/cloud_deskewed' has more than one types associated, rviz will arbitrarily use the type 'sensor_msgs/msg/LaserScan' -- all types for the topic: 'sensor_msgs/msg/LaserScan' 'sensor_msgs/msg/PointCloud2'

          建图需要的是LaserScan,而不是点云,你要把 utlidar/cloud_deskewed 转成LaserScan,或者直接让卖家提供下直接发布laserscan话题的配置方法,一般都支持的

          新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

          Y 1 条回复 最后回复 回复 引用 0
          • Y
            yu @小鱼
            最后由 yu 编辑

            @小鱼 我在节点启动的文件里面,用pointcloud_to_laserscan转了一下,但是我用ros2 topic echo看了一下输出话题的内容,发现里面没有数据,输入话题数据是正常的,不知道是由什么其他问题,pointcloud_to_laserscan的配置文件是:

            pointcloud_to_laserscan_node:
            ros__parameters:
            target_frame: 'odom' # 设置为点云数据的 frame_id
            min_height: -1.0 # 根据需要设置高度过滤范围
            max_height: 3.5 # 根据需要设置高度过滤范围
            angle_min: -1.5708 # 通常为 -π/2(左边)
            angle_max: 1.5708 # 通常为 π/2(右边)
            angle_increment: 0.0174533 # 取决于你的扫描角度分辨率
            range_min: 0.1 # 最小范围
            'scan_time': 0.01
            range_max: 10.0 # 最大范围
            scan_height: 0.1 # 扫描高度
            horizontal_sampling_ratio: 1.0
            vertical_sampling_ratio: 1.0
            keep_organized: true
            

            节点启动代码是:

                # 配置文件
                configuration_basename = LaunchConfiguration('configuration_basename', default='test_dog_2d.lua')
                configuration_convertname = LaunchConfiguration('configuration_convertname', default='pointcloud2_to_laserscan_config.yaml')
            
            
                pointcloud_to_laserscan_node = Node(
                    package='pointcloud_to_laserscan',
                    executable='pointcloud_to_laserscan_node',
                    name='pointcloud_to_laserscan',
                    output='screen',
                    arguments=['-configuration_directory', configuration_directory,
                               '-configuration_convertname', configuration_convertname],
                    # parameters=[{'scan_in': '/utlidar/cloud_deskewed', 'cloud': '/cartographer_scan'}],
                    remappings=[
                    ('/cloud_in', '/utlidar/cloud_deskewed'),
                    ('/scan', '/cartographer_scan')
                    ]
                    )
            

            现在是输出话题/cartographer_scan全是inf了:
            微信图片_20240816144733.jpg

            Y 1 条回复 最后回复 回复 引用 0
            • Y
              yu @yu
              最后由 编辑

              @yu 在 ROS2 foxy cartographer纯激光建图报错 中说:

              @小鱼 我在节点启动的文件里面,用pointcloud_to_laserscan转了一下,但是我用ros2 topic echo看了一下输出话题的内容,发现里面没有数据,输入话题数据是正常的,不知道是由什么其他问题,pointcloud_to_laserscan的配置文件是:

              pointcloud_to_laserscan_node:
              ros__parameters:
              target_frame: 'odom' # 设置为点云数据的 frame_id
              min_height: -1.0 # 根据需要设置高度过滤范围
              max_height: 3.5 # 根据需要设置高度过滤范围
              angle_min: -1.5708 # 通常为 -π/2(左边)
              angle_max: 1.5708 # 通常为 π/2(右边)
              angle_increment: 0.0174533 # 取决于你的扫描角度分辨率
              range_min: 0.1 # 最小范围
              'scan_time': 0.01
              range_max: 10.0 # 最大范围
              scan_height: 0.1 # 扫描高度
              horizontal_sampling_ratio: 1.0
              vertical_sampling_ratio: 1.0
              keep_organized: true
              

              节点启动代码是:

                  # 配置文件
                  configuration_basename = LaunchConfiguration('configuration_basename', default='test_dog_2d.lua')
                  configuration_convertname = LaunchConfiguration('configuration_convertname', default='pointcloud2_to_laserscan_config.yaml')
              
              
                  pointcloud_to_laserscan_node = Node(
                      package='pointcloud_to_laserscan',
                      executable='pointcloud_to_laserscan_node',
                      name='pointcloud_to_laserscan',
                      output='screen',
                      arguments=['-configuration_directory', configuration_directory,
                                 '-configuration_convertname', configuration_convertname],
                      # parameters=[{'scan_in': '/utlidar/cloud_deskewed', 'cloud': '/cartographer_scan'}],
                      remappings=[
                      ('/cloud_in', '/utlidar/cloud_deskewed'),
                      ('/scan', '/cartographer_scan')
                      ]
                      )
              

              现在是输出话题/cartographer_scan全是inf了:
              微信图片_20240816144733.jpg

              但是这种已经可以建图了,只是地图上rviz没有显示点云数据,后面我再看下,感谢

              1 条回复 最后回复 回复 引用 0
              • 第一个帖子
                最后一个帖子
              皖ICP备16016415号-7
              Powered by NodeBB | 鱼香ROS