移动机器人激光SLAM导航(五):Cartographer SLAM 篇

news2024/11/27 2:46:17

参考

  • Cartographer 官方文档
  • Cartographer 从入门到精通

1. Cartographer 安装

1.1 前置条件

  • 推荐在刚装好的 Ubuntu 16.04 或 Ubuntu 18.04 上进行编译
  • ROS 安装:ROS学习1:ROS概述与环境搭建

1.2 依赖库安装

  • 资源下载完解压并执行以下指令
    • https://pan.baidu.com/s/1LWqZ4SOKn2sZecQUDDXXEw?pwd=j6cf
    $ sudo chmod 777 auto-carto-build.sh
    $ ./auto-carto-build.sh
    

1.3 编译

本文只编译 cartographer_ros,以下为同时开三个终端操作

$ mkdir -p cartographer_ws/src
$ cd ~
$ git clone https://github.com/xiangli0608/cartographer_detailed_comments_ws
$ mv ~/cartographer_detailed_comments_ws/src/cartographer_ros ~/cartographer_ws/src
$ cd ~/cartographer_ws
$ catkin_make

2. Cartographer 运行

2.1 数据集下载

  • 百度网盘链接(rslidar-outdoor-gps.bag、landmarks_demo_uncalibrated.bag)
    • https://pan.baidu.com/s/1leRr4JDGg61jBNCwNlSCJw?pwd=5nkq

2.2 配置文件

  • lx_rs16_2d_outdoor.launch

    <launch>
      <!-- bag 的地址与名称(根据自己情况修改,建议使用绝对路径) -->
      <arg name="bag_filename" default="/home/yue/bag/rslidar-outdoor-gps.bag"/>
    
      <!-- 使用 bag 的时间戳 -->
      <param name="/use_sim_time" value="true" />
    
      <!-- 启动 cartographer -->
      <node name="cartographer_node" pkg="cartographer_ros"
          type="cartographer_node" args="
              -configuration_directory $(find cartographer_ros)/configuration_files
              -configuration_basename lx_rs16_2d_outdoor.lua"
          output="screen">
        <remap from="points2" to="rslidar_points" />
        <remap from="scan" to="front_scan" />
        <remap from="odom" to="odom_scout" />
        <remap from="imu" to="imu" />
      </node>
    
      <!-- 生成 ros 格式的地图 -->
      <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
          type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
    
      <!-- 启动 rviz -->
      <node name="rviz" pkg="rviz" type="rviz" required="true"
          args="-d $(find cartographer_ros)/configuration_files/lx_2d.rviz" />
    
      <!-- 启动 rosbag -->
      <node name="playbag" pkg="rosbag" type="play"
          args="--clock $(arg bag_filename)" />
    
    </launch>
    
  • lx_rs16_2d_outdoor.lua

    include "map_builder.lua"
    include "trajectory_builder.lua"
    
    options = {
      map_builder = MAP_BUILDER,               -- map_builder.lua的配置信息
      trajectory_builder = TRAJECTORY_BUILDER, -- trajectory_builder.lua的配置信息
      
      map_frame = "map"-- 地图坐标系的名字
      tracking_frame = "imu_link"-- 将所有传感器数据转换到这个坐标系下
      published_frame = "footprint"-- tf: map -> footprint
      odom_frame = "odom"-- 里程计的坐标系名字
      provide_odom_frame = false-- 是否提供odom的tf,如果为true,则tf树为map->odom->footprint
                                                -- 如果为false tf树为map->footprint
      publish_frame_projected_to_2d = false-- 是否将坐标系投影到平面上
      --use_pose_extrapolator = false,           -- 发布tf时是使用pose_extrapolator的位姿还是前端计算出来的位姿
    
      use_odometry = false-- 是否使用里程计,如果使用要求一定要有odom的tf
      use_nav_sat = false-- 是否使用gps
      use_landmarks = false-- 是否使用landmark
      num_laser_scans = 0-- 是否使用单线激光数据
      num_multi_echo_laser_scans = 0-- 是否使用multi_echo_laser_scans数据
      num_subdivisions_per_laser_scan = 1-- 1帧数据被分成几次处理,一般为1
      num_point_clouds = 1-- 是否使用点云数据
      
      lookup_transform_timeout_sec = 0.2-- 查找tf时的超时时间
      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.,
    }
    
    MAP_BUILDER.use_trajectory_builder_2d = true
    
    TRAJECTORY_BUILDER_2D.use_imu_data = true
    TRAJECTORY_BUILDER_2D.min_range = 0.3
    TRAJECTORY_BUILDER_2D.max_range = 100.
    TRAJECTORY_BUILDER_2D.min_z = 0.2
    --TRAJECTORY_BUILDER_2D.max_z = 1.4
    --TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.02
    
    --TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_length = 0.5
    --TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.min_num_points = 200.
    --TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_range = 50.
    
    --TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_length = 0.9
    --TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.min_num_points = 100
    --TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_range = 50.
    
    TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false
    TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
    TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1.
    TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1.
    --TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 12
    
    --TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.1
    --TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = 0.004
    --TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 1.
    
    TRAJECTORY_BUILDER_2D.submaps.num_range_data = 80.
    TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1
    
    POSE_GRAPH.optimize_every_n_nodes = 160.
    POSE_GRAPH.constraint_builder.sampling_ratio = 0.3
    POSE_GRAPH.constraint_builder.max_constraint_distance = 15.
    POSE_GRAPH.constraint_builder.min_score = 0.48
    POSE_GRAPH.constraint_builder.global_localization_min_score = 0.60
    
    return options
    
  • trajectory_builder_2d.lua

    TRAJECTORY_BUILDER_2D = {
      use_imu_data = true,            -- 是否使用imu数据
      min_range = 0.,                 -- 雷达数据的最远最近滤波, 保存中间值
      max_range = 30.,
      min_z = -0.8,                   -- 雷达数据的最高与最低的过滤, 保存中间值
      max_z = 2.,
      missing_data_ray_length = 5.,   -- 超过最大距离范围的数据点用这个距离代替
      num_accumulated_range_data = 1, -- 几帧有效的点云数据进行一次扫描匹配
      voxel_filter_size = 0.025,      -- 体素滤波的立方体的边长
    
      -- 使用固定的voxel滤波之后, 再使用自适应体素滤波器
      -- 体素滤波器 用于生成稀疏点云 以进行 扫描匹配
      adaptive_voxel_filter = {
        max_length = 0.5,             -- 尝试确定最佳的立方体边长, 边长最大为0.5
        min_num_points = 200,         -- 如果存在 较多点 并且大于'min_num_points', 则减小体素长度以尝试获得该最小点数
        max_range = 50.,              -- 距远离原点超过max_range 的点被移除
      },
    
      -- 闭环检测的自适应体素滤波器, 用于生成稀疏点云 以进行 闭环检测
      loop_closure_adaptive_voxel_filter = {
        max_length = 0.9,
        min_num_points = 100,
        max_range = 50.,
      },
    
      -- 是否使用 real_time_correlative_scan_matcher 为ceres提供先验信息
      -- 计算复杂度高 , 但是很鲁棒 , 在odom或者imu不准时依然能达到很好的效果
      use_online_correlative_scan_matching = false,
      real_time_correlative_scan_matcher = {
        linear_search_window = 0.1,             -- 线性搜索窗口的大小
        angular_search_window = math.rad(20.),  -- 角度搜索窗口的大小
        translation_delta_cost_weight = 1e-1,   -- 用于计算各部分score的权重
        rotation_delta_cost_weight = 1e-1,
      },
    
      -- ceres匹配的一些配置参数
      ceres_scan_matcher = {
        occupied_space_weight = 1.,
        translation_weight = 10.,
        rotation_weight = 40.,
        ceres_solver_options = {
          use_nonmonotonic_steps = false,
          max_num_iterations = 20,
          num_threads = 1,
        },
      },
    
      -- 为了防止子图里插入太多数据, 在插入子图之前之前对数据进行过滤
      motion_filter = {
        max_time_seconds = 5.,
        max_distance_meters = 0.2,
        max_angle_radians = math.rad(1.),
      },
    
      -- TODO(schwoere,wohe): Remove this constant. This is only kept for ROS.
      imu_gravity_time_constant = 10.,
    
      -- 位姿预测器
      pose_extrapolator = {
        use_imu_based = false,
        constant_velocity = {
          imu_gravity_time_constant = 10.,
          pose_queue_duration = 0.001,
        },
        imu_based = {
          pose_queue_duration = 5.,
          gravity_constant = 9.806,
          pose_translation_weight = 1.,
          pose_rotation_weight = 1.,
          imu_acceleration_weight = 1.,
          imu_rotation_weight = 1.,
          odometry_translation_weight = 1.,
          odometry_rotation_weight = 1.,
          solver_options = {
            use_nonmonotonic_steps = false;
            max_num_iterations = 10;
            num_threads = 1;
          },
        },
      },
    
      -- 子图相关的一些配置
      submaps = {
        num_range_data = 90,          -- 一个子图里插入雷达数据的个数的一半
        grid_options_2d = {
          grid_type = "PROBABILITY_GRID", -- 地图的种类, 还可以是tsdf格式
          resolution = 0.05,
        },
        range_data_inserter = {
          range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
          -- 概率占用栅格地图的一些配置
          probability_grid_range_data_inserter = {
            insert_free_space = true,
            hit_probability = 0.55,
            miss_probability = 0.49,
          },
          -- tsdf地图的一些配置
          tsdf_range_data_inserter = {
            truncation_distance = 0.3,
            maximum_weight = 10.,
            update_free_space = false,
            normal_estimation_options = {
              num_normal_samples = 4,
              sample_radius = 0.5,
            },
            project_sdf_distance_to_scan_normal = true,
            update_weight_range_exponent = 0,
            update_weight_angle_scan_normal_to_ray_kernel_bandwidth = 0.5,
            update_weight_distance_cell_to_hit_kernel_bandwidth = 0.5,
          },
        },
      },
    }
    
  • pose_graph.lua

    POSE_GRAPH = {
      -- 每隔多少个节点执行一次后端优化
      optimize_every_n_nodes = 90,
    
      -- 约束构建的相关参数
      constraint_builder = {
        sampling_ratio = 0.3,                 -- 对局部子图进行回环检测时的计算频率, 数值越大, 计算次数越多
        max_constraint_distance = 15.,        -- 对局部子图进行回环检测时能成为约束的最大距离
        min_score = 0.55,                     -- 对局部子图进行回环检测时的最低分数阈值
        global_localization_min_score = 0.6,  -- 对整体子图进行回环检测时的最低分数阈值
        loop_closure_translation_weight = 1.1e4,
        loop_closure_rotation_weight = 1e5,
        log_matches = true,                   -- 打印约束计算的log
        
        -- 基于分支定界算法的2d粗匹配器
        fast_correlative_scan_matcher = {
          linear_search_window = 7.,
          angular_search_window = math.rad(30.),
          branch_and_bound_depth = 7,
        },
    
        -- 基于ceres的2d精匹配器
        ceres_scan_matcher = {
          occupied_space_weight = 20.,
          translation_weight = 10.,
          rotation_weight = 1.,
          ceres_solver_options = {
            use_nonmonotonic_steps = true,
            max_num_iterations = 10,
            num_threads = 1,
          },
        },
    
        -- 基于分支定界算法的3d粗匹配器
        fast_correlative_scan_matcher_3d = {
          branch_and_bound_depth = 8,
          full_resolution_depth = 3,
          min_rotational_score = 0.77,
          min_low_resolution_score = 0.55,
          linear_xy_search_window = 5.,
          linear_z_search_window = 1.,
          angular_search_window = math.rad(15.),
        },
    
        -- 基于ceres的3d精匹配器
        ceres_scan_matcher_3d = {
          occupied_space_weight_0 = 5.,
          occupied_space_weight_1 = 30.,
          translation_weight = 10.,
          rotation_weight = 1.,
          only_optimize_yaw = false,
          ceres_solver_options = {
            use_nonmonotonic_steps = false,
            max_num_iterations = 10,
            num_threads = 1,
          },
        },
      },
    
      matcher_translation_weight = 5e2,
      matcher_rotation_weight = 1.6e3,
    
      -- 优化残差方程的相关参数
      optimization_problem = {
        huber_scale = 1e1,                -- 值越大,(潜在)异常值的影响就越大
        acceleration_weight = 1.1e2,      -- 3d里imu的线加速度的权重
        rotation_weight = 1.6e4,          -- 3d里imu的旋转的权重
        
        -- 前端结果残差的权重
        local_slam_pose_translation_weight = 1e5,
        local_slam_pose_rotation_weight = 1e5,
        -- 里程计残差的权重
        odometry_translation_weight = 1e5,
        odometry_rotation_weight = 1e5,
        -- gps残差的权重
        fixed_frame_pose_translation_weight = 1e1,
        fixed_frame_pose_rotation_weight = 1e2,
        fixed_frame_pose_use_tolerant_loss = false,
        fixed_frame_pose_tolerant_loss_param_a = 1,
        fixed_frame_pose_tolerant_loss_param_b = 1,
    
        log_solver_summary = false,
        use_online_imu_extrinsics_in_3d = true,
        fix_z_in_3d = false,
        ceres_solver_options = {
          use_nonmonotonic_steps = false,
          max_num_iterations = 50,
          num_threads = 7,
        },
      },
    
      max_num_final_iterations = 200,   -- 在建图结束之后执行一次全局优化, 不要求实时性, 迭代次数多
      global_sampling_ratio = 0.003,    -- 纯定位时候查找回环的频率
      log_residual_histograms = true,
      global_constraint_search_after_n_seconds = 10., -- 纯定位时多少秒执行一次全子图的约束计算
    
      --  overlapping_submaps_trimmer_2d = {
      --    fresh_submaps_count = 1,
      --    min_covered_area = 2,
      --    min_added_submaps_count = 5,
      --  },
    }
    

2.3 运行演示

$ source devel/setup.bash
$ roslaunch cartographer_ros lx_rs16_2d_outdoor.launch

在这里插入图片描述

3. Cartographer 调参总结

3.1 降低延迟与减小计算量

  • 前端

    • 减小 max_range 即减小了需要处理的点数,在激光雷达远距离的数据点不准时一定要减小这个值
    • 增大 voxel_filter_size,相当于减小了需要处理的点数
    • 增大 submaps.resolution,相当于减小了匹配时的搜索量
    • 对于自适应体素滤波 减小 min_num_points 与 max_range,增大 max_length,相当于减小了需要处理的点数
  • 后端

    • 减小 optimize_every_n_nodes, 降低优化频率, 减小了计算量
    • 增大 MAP_BUILDER.num_background_threads, 增加计算速度
    • 减小 global_sampling_ratio, 减小计算全局约束的频率
    • 减小 constraint_builder.sampling_ratio, 减少了约束的数量
    • 增大 constraint_builder.min_score, 减少了约束的数量
    • 减小分枝定界搜索窗的大小, 包括linear_xy_search_window,inear_z_search_window, angular_search_window
    • 增大 global_constraint_search_after_n_seconds, 减小计算全局约束的频率
    • 减小 max_num_iterations, 减小迭代次数

3.2 降低内存

  • 增大子图的分辨率 submaps.resolution

3.3 常调的参数

TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 100.
TRAJECTORY_BUILDER_2D.min_z = 0.2 -- / -0.8
TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.02
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 10.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1.
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 80.
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1 -- / 0.02
POSE_GRAPH.optimize_every_n_nodes = 160. -- 2倍的num_range_data以上
POSE_GRAPH.constraint_builder.sampling_ratio = 0.3
POSE_GRAPH.constraint_builder.max_constraint_distance = 15.
POSE_GRAPH.constraint_builder.min_score = 0.48
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.60

4. Cartographer 工程化建议

4.1 如何提升建图质量

  • 选择频率高(25 Hz 以上)、精度高的激光雷达
  • 如果只能用频率低的激光雷达
    • 使用高频、高精度 IMU,且让机器人运动慢一点
    • 调 ceres 的匹配权重,将地图权重调大,平移旋转权重调小
    • 将代码中平移和旋转的残差注释掉
  • 里程计
    • Cartographer 中对里程计的使用不太好
    • 可以将 karto 与 GMapping 中使用里程计进行预测的部分拿过来进行使用,改完后就可达到比较好的位姿预测效果
  • 粗匹配
    • 将 karto 的扫描匹配的粗匹配放过来,karto 的扫描匹配的计算量很小,当做粗匹配很不错
  • 地图
    • 在最终生成地图的时候使用后端优化后的节点重新生成一次地图,这样生成的地图效果会比前端地图的叠加要好很多

4.2 降低计算量与内存

  • 体素滤波与自适应体素滤波的计算量(不是很大)
  • 后端进行子图间约束时的计算量很大
  • 分支定界算法的计算量很大
  • 降低内存,内存的占用基本就是多分辨率地图,每个子图的多分辨率地图都进行保存是否有必要

4.3 纯定位的改进建议

  • 将纯定位模式与建图拆分开,改成读取之前轨迹的地图进行匹配.
  • 新的轨迹只进行位姿预测,拿到预测后的位姿与之前轨迹的地图进行匹配,新的轨迹不再进行地图的生成与保存,同时将整个后端的功能去掉.
  • 去掉后端优化会导致没有重定位功能,这时可将 cartographer 的回环检测(子图间约束的计算)部分单独拿出来,做成一个重定位功能,通过服务来调用这个重定位功能,根据当前点云确定机器人在之前地图的位姿

4.4 去 ros 的参考思路

  • 仿照 cartographer_ros 里的操作:获取到传感器数据,将数据转到 tracking_frame 坐标系下并进行格式转换,再传入到 cartographer 里就行

5. 源码注释

  • cartographer_detailed_comments_ws

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/1448837.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

Python 读取pdf文件

Python 实现读取pdf文件简单示例。 安装命令 需要安装操作pdf的三方类库&#xff0c;命令如下&#xff1a; pip install pdfminer3K 安装过程如下&#xff1a; 引入类库 需要引入很多的类库。 示例如下&#xff1a; import sys import importlib importlib.reload(sys)fr…

鸿蒙开发系列教程(十八)--页面内动画(1)

页面内的动画 显示动画 语法&#xff1a;animateTo(value: AnimateParam, event: () > void): void 第一个参数指定动画参数 第二个参数为动画的闭包函数。 如&#xff1a;animateTo({ duration: 1000, curve: Curve.EaseInOut }, () > {动画代码}&#xff09; dura…

Golang快速入门到实践学习笔记

Go学习笔记 1.基础 Go程序设计的一些规则 Go之所以会那么简洁&#xff0c;是因为它有一些默认的行为&#xff1a; 大写字母开头的变量是可导出的&#xff0c;也就是其它包可以读取 的&#xff0c;是公用变量&#xff1b;小写字母开头的就是不可导出的&#xff0c;是私有变量…

cool-node.js 框架 创建数据表的步骤

1.文件目录 business 这个模块的数据库对应的就是 entity文件夹 这一个文件.ts 就是代表了一个表 2.user.ts 表的介绍 这个 相当于 时 固定格式的数据表 &#xff0c;只需要按照这个 格式和创建表的方式来创建就可以 BusinessUserEntity 相当于时这个数据表类的名字 Entity(b…

FPGA_简单工程_拨码开关

一 框图 二 波形图 三 代码 3.1 工程代码 module bomakiaguan (input [15:0] switch, // 输入16路拨码开关output reg [15:0] led // 输出16个LED灯 );always (switch) beginled < switch; // 将拨码开关的值直接赋给LED灯 end // 将拨码开关的值直接赋给LED灯 endmodu…

五.实战软件部署 4-5MYSQL 5.7版本在ubuntu(WSL环境)安装MYSQL 8.0版本在ubuntu(WSL环境)安装

目录 五.实战软件部署 4-MYSQL 5.7版本在ubuntu(WSL环境)安装 安装 1-下载apt仓库文件 2-配置apt仓库 3-更新apt仓库的信息 4-检查是否成功配置mysql5.7的仓库 5-安装mysql5.7 6-启动mysql 7-对mysql进行初始化 1-输入密码 2-是否开启密码验证插件&#xff0c;如果需…

二叉树的顺序结构及堆的实现

创作不易&#xff0c;兄弟们给个三连&#xff01;&#xff01; 一、二叉树的顺序存储 顺序结构指的是利用数组来存储&#xff0c;一般只适用于表示完全二叉树&#xff0c;原因如上图&#xff0c;存储不完全二叉树会造成空间上的浪费&#xff0c;有的人又会问&#xff0c;为什么…

ELAdmin 部署

后端部署 按需修改 application-prod.yml 例如验证码方式、登录状态到期时间等等。 修改完成后打好 Jar 包 执行完成后会生成最终可执行的 jar。JPA版本是 2.6&#xff0c;MyBatis 版本是 1.1。 启动命令 nohup java -jar eladmin-system-2.6.jar --spring.profiles.active…

探索微信小程序的奇妙世界:从入门到进阶

文章目录 一、什么是微信小程序1.1 简要介绍微信小程序的定义和特点1.2 解释小程序与传统应用程序的区别 二、小程序的基础知识2.1 微信小程序的架构2.2 微信小程序生命周期的理解2.3 探索小程序的目录结构和文件类型 三、小程序框架和组件3.1 深入了解小程序框架的核心概念和原…

【JavaEE】_JavaScript(Web API)

目录 1. DOM 1.1 DOM基本概念 1.2 DOM树 2. 选中页面元素 2.1 querySelector 2.2 querySelectorAll 3. 事件 3.1 基本概念 3.2 事件的三要素 3.3 示例 4.操作元素 4.1 获取/修改元素内容 4.2 获取/修改元素属性 4.3 获取/修改表单元素属性 4.3.1 value&#xf…

nba2k24 灌篮高手樱木花道面补

nba2k24 灌篮高手樱木花道面补 nba2k23-nba2k24通用 灌篮高手樱木花道面补 下载地址&#xff1a; https://www.changyouzuhao.cn/9539.html

linux系统配置zabbix监控agent端

目录 客户端配置 启动服务 浏览器工具设置 创建主机群组 创建主机 创建监控项 ​编辑 ​编辑 创建触发器 查看监控 客户端配置 rpm -Uvh https://repo.zabbix.com/zabbix/5.0/rhel/7/x86_64/zabbix-release-5.0-1.el7.noarch.rpm # yum clean allyum install -y zab…

【Python】Python代码的单元测试

Python代码的单元测试 单元测试的概念 定义&#xff1a;是指对软件中的最小可测试单元进行检查和验证。 作用&#xff1a;可以确保程序模块是否否和我们规范的输出&#xff0c;保证该模块经过修改后仍然是满足我们的需求。 单元测试的策略 如果要创建单元测试&#xff0c;…

2024最新APP下载单页源码 带管理后台 首发

2024最新APP下载单页源码 带管理后台 首发 新版带后台管理app应用下载页,自动识别安卓苹果下载页&#xff0c;带管理后台&#xff0c;内置带3套App下载模板带中文模板/英文模板随时切换。 下载地址2023最新APP下载单页源码 带管理后台 .zip官方版下载丨最新版下载丨绿色版下载…

重复导航到当前位置引起的。Vue Router 提供了一种机制,阻止重复导航到相同的路由路径。

代码&#xff1a; <!-- 侧边栏 --><el-col :span"12" :style"{ width: 200px }"><el-menu default-active"first" class"el-menu-vertical-demo" select"handleMenuSelect"><el-menu-item index"…

深度学习-吴恩达L1W2作业

作业1&#xff1a;吴恩达《深度学习》L1W2作业1 - Heywhale.com 作业2&#xff1a;吴恩达《深度学习》L1W2作业2 - Heywhale.com 作业1 你需要记住的内容&#xff1a; -np.exp&#xff08;x&#xff09;适用于任何np.array x并将指数函数应用于每个坐标 -sigmoid函数及其梯度…

【教学类-16-02】20240214《数字卡片1-9(正方形)华光彩云_CNKI》

背景需求&#xff1a; 前期坐过长方形A4纸的数字卡片 【教学类-16-01】20221121《数字卡片9*2》&#xff08;中班)_数字卡片pdf-CSDN博客文章浏览阅读897次。【教学类-16-01】20221121《数字卡片9*2》&#xff08;中班)_数字卡片pdfhttps://blog.csdn.net/reasonsummer/artic…

B端系统从0到1:有几步,其中需求分析要做啥?

一款B系统从无到有都经历了啥&#xff0c;而其中的需求分析又要做什么&#xff1f;贝格前端工场给老铁们做一下分析&#xff0c;文章写作不易&#xff0c;如果咱们有界面设计和前端开发需求&#xff0c;别忘了私信我呦&#xff0c;开始了。 一、B端系统从0到1都有哪些要走的步骤…

第13章 网络 Page729~733 链式任务反应

链式任务反应 当io_service对象身上没有任务的时候&#xff0c;当前正在运行的run()过程就结束了。这时再往它身上添加任务&#xff0c;程序收不到任务完成事件。 如果本次任务完成后&#xff0c;run()函数退出前再添加一项或更多任务&#xff0c;这就叫链式任务。 在asio的…

日志监控须知

在这个领域,最流行的应该是ELK. ELK可以让收集日志,检索日志更加的简单,让定位日志问题更加的高效,在也不需要挨个登录服务器,然后用一堆Linux命令去搜索日志了. ELK ( Elasticsearch Logstash Kibana ) ELK架构: 各个微服务,通过某种机制把自己的日志交给Logstash 这里的某…