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

    cartographer 如何配置倾斜的3d雷达和imu

    已定时 已固定 已锁定 已移动
    VIP问答专区
    cartographer imu lidar
    1
    5
    95
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • R
      realez 年度VIP
      最后由 编辑

      雷达自带imu,机器人自身也有配imu,当前雷达是倾斜放置的,为了有一定高度同时探测地面低矮的障碍物,尝试了一些配置,有以下问题
      1:如果tracking_frame配置为base_link,会报错,要求imu的frame id和base_link不能离太远,3d建图配置里没找到哪里可以禁用imu
      2:如果tracking_frame配置为imu的frame id,则rviz中map会倾斜,导致地图都是灰色或黑色

      两个imu都没有和base_link重合

      1 条回复 最后回复 回复 引用 0
      • R
        realez 年度VIP
        最后由 编辑

        2573a5f4-b322-4198-93f2-c8f51915145e-image.png

        1 条回复 最后回复 回复 引用 0
        • R
          realez 年度VIP
          最后由 编辑

          -- Copyright 2016 The Cartographer Authors

          -- Licensed under the Apache License, Version 2.0 (the "License");
          -- you may not use this file except in compliance with the License.
          -- You may obtain a copy of the License at

          -- http://www.apache.org/licenses/LICENSE-2.0

          -- Unless required by applicable law or agreed to in writing, software
          -- distributed under the License is distributed on an "AS IS" BASIS,
          -- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
          -- See the License for the specific language governing permissions and
          -- limitations under the License.

          include "map_builder.lua"
          include "trajectory_builder.lua"

          options = {
          map_builder = MAP_BUILDER,
          trajectory_builder = TRAJECTORY_BUILDER,
          map_frame = "map",
          tracking_frame = "livox_frame",
          published_frame = "base_link",
          odom_frame = "odom",
          provide_odom_frame = false,
          publish_frame_projected_to_2d = false,
          use_odometry = false,
          use_nav_sat = false,
          use_landmarks = false,
          num_laser_scans = 0,
          num_multi_echo_laser_scans = 0,
          num_subdivisions_per_laser_scan = 1,
          num_point_clouds = 1,
          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.,
          }

          TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 1
          TRAJECTORY_BUILDER_3D.min_range = 0.2
          TRAJECTORY_BUILDER_3D.max_range = 20.
          TRAJECTORY_BUILDER_2D.min_z = 0.1
          TRAJECTORY_BUILDER_2D.max_z = 1.0
          TRAJECTORY_BUILDER_3D.use_online_correlative_scan_matching = false

          MAP_BUILDER.use_trajectory_builder_3d = true
          MAP_BUILDER.num_background_threads = 4
          POSE_GRAPH.optimization_problem.huber_scale = 5e2
          POSE_GRAPH.optimize_every_n_nodes = 40
          POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
          POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 20
          POSE_GRAPH.constraint_builder.min_score = 0.5
          POSE_GRAPH.constraint_builder.global_localization_min_score = 0.55

          POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e3
          POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e3

          return options

          1 条回复 最后回复 回复 引用 0
          • R
            realez 年度VIP
            最后由 编辑

            f3edeca8-ae2a-472f-9374-a8c6aaab0d17-image.png
            当使用水平的imu时,tracking_frame改为水平imu的frameid,map是水平的了,但是点云会穿透map,整个地图都会变成灰色或黑色,无法有效建图

            1 条回复 最后回复 回复 引用 0
            • R
              realez 年度VIP
              最后由 编辑

              用pcl把点云转到base_link坐标系下,使用passthrough过滤掉z轴0.05一下的数据即可

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