cartographer1.0 纯定位模式改变

1.0版本已有的纯定位模式,只是做了一件事情-限制submaps的搜索数目,230509。

纯定位模式并没有离开slam模式和优化过程,只是限制了kSubmapsToKeep=3 选项。且整个工程只使用了pure_loaction一次这个选项!!!

int MapBuilder::AddTrajectoryBuilder(
    const std::set<SensorId>& expected_sensor_ids,
    const proto::TrajectoryBuilderOptions& trajectory_options,
LocalSlamResultCallback local_slam_result_callback) {
............................
  if (trajectory_options.pure_localization()) {
    constexpr int kSubmapsToKeep = 3;
    pose_graph_->AddTrimmer(common::make_unique<PureLocalizationTrimmer>(
        trajectory_id, kSubmapsToKeep));
  }
............................
}

纯定位模式入口

    // 位于文件 map_builder.cc

    void MaybeAddPureLocalizationTrimmer(
        const int trajectory_id,
        const proto::TrajectoryBuilderOptions& trajectory_options,
        PoseGraph* pose_graph) {
      if (trajectory_options.pure_localization())

{
        // 已经被弃用了,现在是改为使用pure_localization_trimmer
        LOG(WARNING)
            << "'TrajectoryBuilderOptions::pure_localization' field is deprecated. "
               "Use 'TrajectoryBuilderOptions::pure_localization_trimmer' instead.";
        pose_graph->AddTrimmer(absl::make_unique<PureLocalizationTrimmer>(
            trajectory_id, 3 /* max_submaps_to_keep */));
        return;
      }
      if (trajectory_options.has_pure_localization_trimmer()) {
        pose_graph->AddTrimmer(absl::make_unique<PureLocalizationTrimmer>(
            trajectory_id,
            trajectory_options.pure_localization_trimmer().max_submaps_to_keep()));
      }
    }
     
    // 对应的 proto : cartographer/mapping/proto/trajectory_builder_options.proto
    message TrajectoryBuilderOptions {
      LocalTrajectoryBuilderOptions2D trajectory_builder_2d_options = 1;
      LocalTrajectoryBuilderOptions3D trajectory_builder_3d_options = 2;
      InitialTrajectoryPose initial_trajectory_pose = 4;
     
      reserved 5;
     
      bool pure_localization = 3 [deprecated = true];// deprecated 被弃用
      message PureLocalizationTrimmerOptions {
        int32 max_submaps_to_keep = 1;
      }
      PureLocalizationTrimmerOptions pure_localization_trimmer = 6;
     
      bool collate_fixed_frame = 7;
      bool collate_landmarks = 8;
    }


 

使用Proto参数的方式

1. Message 

2.lua参数配置文件,通过字典获取

1)读取lua文件

       通过读取生成lua字典


2)赋值给proto options

     其赋值主要有两种方式:
    - 1. options.set_变量名(参数值)
    - 2. options.mutable_变量名 = 参数值

   获取proto参数值有两种方式:1)lua文件 2)通过service,例如如下代码中 InitialTrajectoryPose 的赋值

    // 如下代码位于: cartographer_ros/node.cc
 

    // cartographer_ros_msgs::StartTrajectory 是自定义的service,位于cartographer_ros_msgs/srv/StartTrajectory.srv
     
    bool Node::HandleStartTrajectory(
        ::cartographer_ros_msgs::StartTrajectory::Request& request,
        ::cartographer_ros_msgs::StartTrajectory::Response& response) {
     
    // 这个是在cartographer_ros/trajectory_options.h 中 自定义的类,与proto中的不同。
    // 该类型包含了
    // cartographer::mapping::proto::TrajectoryBuilderOptions 变量
    // 和 一些其他的topic,频率等变量(这些变量会根据数据集的不同可能会变化,因此在最外层)。
    // 对应 cartographer_ros/configuration_files/backpack_2d.lua 等文件
    // 这些lua文件全部       include "map_builder.lua"
    //                     include "trajectory_builder.lua"
    // 所以,核心的lua还是 map_builder.lua; trajectory_builder.lua
    // 而 map_builder.lua; trajectory_builder.lua 又分别包含其他的很多lua 就这样一层一层的。
     
      TrajectoryOptions trajectory_options;
     
      // 将lua转换为 proto options
      // tie 可以将tuple解包,赋值给相应的参数。std::ignore 表示忽略第一个参数
      std::tie(std::ignore, trajectory_options) = LoadOptions(
          request.configuration_directory, request.configuration_basename);
..................................
      
      // 可以注意到:cartographer/configuration_files/trajectory_builder.lua中,
      // 并没有给InitialTrajectoryPose 这个变量赋值,虽然 proto中包含这个变量
      // 而是留到service中进行赋值
     
      if (request.use_initial_pose) {
     
      // InitialTrajectoryPose 是在 cartographer/mapping/proto/trajectory_builder_options.proto
    // 中定义的一个 options , 其赋值主要有两种方式:
    // 1. options.set_变量名(参数值)
    // 2. options.mutable_变量名 = 参数值
    // 注意:options 也是一个成员变量,其赋值也是使用上述两种方式之一
     
          ::cartographer::mapping::proto::InitialTrajectoryPose
            initial_trajectory_pose;
        initial_trajectory_pose.set_to_trajectory_id(
            request.relative_to_trajectory_id);
        *initial_trajectory_pose.mutable_relative_pose() =
            cartographer::transform::ToProto(pose);
        initial_trajectory_pose.set_timestamp(cartographer::common::ToUniversal(
            ::cartographer_ros::FromRos(ros::Time(0))));
        *trajectory_options.trajectory_builder_options
             .mutable_initial_trajectory_pose() = initial_trajectory_pose;
     
    }
     
    }

但是,需要注意的是,在node.cc里面配置的,还是不能传递到C++,需要在C++里面同步配置!或者重写一个调用函数接口!

  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值