一、 RoboSense 16线雷达驱动安装 2
二、 Cartographer的安装 2
三、 配置文件结构说明 4
四、 配置文件详解 4
2D lua文件的配置 5
2D launch文件的配置 6
2D pure location lua文件的配置 7
2D pure location launch文件的配置 7
3D lua文件的配置 8
3D launch文件的配置 9
3D pure location lua文件的配置 10
3D pure location launch文件的配置 10
Assets writer 3D lua文件的配置 11
Assets writer 3D launch文件的配置 12
五、 建图命令 12
六、 纯定位命令 13
七、 导航文件配置 13
launch文件的配置 13
move_base_params.yaml文件参数 15
costmap_common_params.yaml文件参数 16
local_costmap_params.yaml 文件参数 17
global_costmap_params.yaml文件参数 18
dwa_local_planner_params.yaml文件参数 18
navfn_global_planner_params.yaml文件参数 19
八、 导航命令 20
九、 发送目标点的导航路线规划 20
十、 导航探索SLAM 20
十一、 其余功能包说明 21
1. imu_pub 21
2. odom_pub(未用到) 21
3. cmd_vel_to_stm 21
4. pointcloud_to_laserscan 21
参数设置请参照wiki.ros.org/pointcloud_to_laserscan 21
十二、 相关博客推荐 21
Ros版本:ROS-Kinect
工作目录:~/carto_ws
安装依赖项
$>> sudo apt-get install libpcap-dev
下载源码到工作目录的src/文件夹下
$>> cd ~/carto_ws/src
$>> git clone https://github.com/RoboSense-LiDAR/ros_rslidar
修改文件权限
$>> cd ~/carto_ws/src/ros_rslidar/rslidar_drvier
$>> chmod 777 cfg/*
$>> cd ~/carto_ws/src/ros_rslidar/rslidar_pointcloud
$>> chmod 777 cfg/*
源码编译
$>> cd ~/carto_ws
$>> catkin_make
设置电脑的静态ip地址
$>> sudo gedit /etc/networsk/interfaces
设置eth0(有些是eth1,或者eno0等,根据自己的网口修改),修改或增加内容如下:
# interfaces eth0 for rslidar connect
auto eth0
iface eth0 inet static
address 192.168.1.102
netmask 255.255.255.0
gateway 192.168.1.1
连接雷达电源和网线,重启电脑。
$>> cd carto_ws
$>> source devel/setup.bash
$>> roslaunch rslidar_pointcloud rs_lidar_16.launch
可以在RVIZ中看到点云,注意要设置全局坐标系为rslidar。
cartographer的安装主要是ceres、prtobuf和cartographer的安装,cartographer_ros是ROS的功能包,调用cartographer算法。
安装依赖:
$>> sudo apt-get update
$>> sudo apt-get install -y python-wstool python-rosdep ninja-build
安装Ceres solver
$>> cd ~/carto_ws/document
$>> git clone https://github.com/BlueWhaleRobot/ceres-solver.git
$>> cd ceres-solver
$>> mkdir build
$>> cd build
$>> cmake ..
$>> make -j
$>> sudo make install
安装Prtobuf 3.0
$>> cd ~/carto_ws/document
$>> git clone https://github.com/google/protobuf.git
$>> cd protobuf
$>> git checkout v3.6.1
$>> mkdir build
$>> cd build
$>> cmake \
-DCMAKE_POSITION_INDEPENDENT_CODE=ON \
-DCMAKE_BUILD_TYPE=Release \
-Dprotobuf_BUILD_TESTS=OFF \
../cmake
$>> make -j 2
$>> sudo make install
安装Cartographer
$>> cd ~/carto_ws/document
$>> git clone https://github.com/BlueWhaleRobot/cartographer.git
$>> cd cartographer
$>> mkdir build
$>> cd build
$>> cmake ..
$>> make -j
$>> sudo make install
安装cartographer_ros
$>> cd ~/carto_ws/src #请修改路径到自己的ROS catkin工作空间
$>> git clone https://github.com/BlueWhaleRobot/cartographer_ros.git
$>> cd ..
$>> catkin_make_isolated --install --use-ninja
测试
下载文件:https://www.bwbot.org/s/vQ2D9Z
然后运行。根据个人平台计算能力不同,完整运行时间一般为半个小时到1个小时之间
$>> source devel_ioslated/setup.bash
$>> roslaunch cartographer_ros offline_backpack_2d.launch bag_filenames:=${HOME}/Desktop/cartographer_paper_deutsches_museum.bag
##修改到自己保存的路径
提取建立的地图,结束测试
上面步骤会生成一个pbstream文件,用cartographer_ assets_writer可以转换成ROS使用的栅格地图。
$>> roslaunch cartographer_ros assets_writer_ros_map.launch bag_filenames:=${HOME}/Desktop/cartographer_paper_deutsche
工作目录为carto_ws,src同级目录除了编译产生的,其余都是安装依赖留下的文件夹。
Cartographer配置文件主要存在src/cartographer_ros/cartographer_ros下的urdf文件夹的myself_robot.urdf、configuration文件夹下的myself_rslidar_2(3)d.lua,myself_backpack_2(3)d_localization.lua以及rslidar_2(3)d.rviz、demo_2d.rviz配置文件、launch文件夹下的myself_rslidar_2(3)d.launch、myself_backpack_2(3)d_localization.launch。这里定位由于和后面导航rviz显示冲突,注释了rviz,纯定位时需要取消注释,显示调用rviz。
在3D建图还需要后面进行离线处理,需要assets_writer_myself_3d.launch,其中相关的配置文件为 assets_writer_myself_3d.lua。
利用bag包进行离线3D SLAM建图可以使用offline_myself_rslidar_3d.launch
URDF文件的配置(这里2D和3D都是使用的同一个urdf):
2D lua文件的配置
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map", #这个是地图坐标系名称
tracking_frame = "imu",#设置为IMU的坐标系
published_frame = "base_link",#设置为机器人基底坐标系
odom_frame = "odom",#里程计坐标系名称
provide_odom_frame = true,#发布base_link->odom的tf变化,否则发布base_link->map
publish_frame_projected_to_2d = false, #如果启用,发布的姿态将被限制为纯2D姿态(无滚动、俯仰或z-偏移)。
use_odometry = false,#是否使用编码器提供odom
use_nav_sat = false,#是否使用gps
use_landmarks = false,#是否使用路标
num_laser_scans = 0,#使用2d 雷达的数量
num_multi_echo_laser_scans = 0,#使用 echo_laser的数量
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 1, #使用3D雷达的数量
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
MAP_BUILDER.use_trajectory_builder_3d = true
MAP_BUILDER.num_background_threads = 7
POSE_GRAPH.optimization_problem.huber_scale = 5e2
POSE_GRAPH.optimize_every_n_nodes = 320
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
POSE_GRAPH.constraint_builder.min_score = 0.62
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66
return options
其他参数,参考链接:
https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html
2D launch文件的配置
textfile="$(find cartographer_ros)/urdf/myself_robot.urdf" />
type="robot_state_publisher" /> type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename myself_rslidar_2d.lua" output="screen"> args="-d $(find cartographer_ros)/configuration_files/rslidar_2d.rviz" /> 2D pure location lua文件的配置 include "myself_rslidar_2d.lua" TRAJECTORY_BUILDER.pure_localization = true POSE_GRAPH.optimize_every_n_nodes = 20 --fast location MAP_BUILDER.num_background_threads=8 POSE_GRAPH.constraint_builder.sampling_ratio=0.5*POSE_GRAPH.constraint_builder.sampling_ratio POSE_GRAPH.global_sampling_ratio=0.1*POSE_GRAPH.global_sampling_ratio POSE_GRAPH.max_num_final_iterations=1 return options 2D pure location launch文件的配置
textfile="$(find cartographer_ros)/urdf/myself_robot.urdf" /> type="robot_state_publisher" /> type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename myself_backpack_2d_localization.lua -load_state_filename /home/dcz/bag/map.pbstream" output="screen"> type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> 3D lua文件的配置 include "map_builder.lua" include "trajectory_builder.lua" options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "imu", published_frame = "base_link", odom_frame = "odom", provide_odom_frame = true, 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 --change 当三维点云效果不好时使用离线建图方法,这里为离线建图需要调整的参数 TRAJECTORY_BUILDER_3D.min_range = 0.2 TRAJECTORY_BUILDER_3D.max_range = 30. --need try --TRAJECTORY_BUILDER_2D.min_z = 0.1 --TRAJECTORY_BUILDER_2D.max_z = 1.0 MAP_BUILDER.use_trajectory_builder_3d = true MAP_BUILDER.num_background_threads = 7 POSE_GRAPH.optimization_problem.huber_scale = 5e2 POSE_GRAPH.optimize_every_n_nodes = 320 POSE_GRAPH.constraint_builder.sampling_ratio = 0.03 POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10 POSE_GRAPH.constraint_builder.min_score = 0.62 POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66 return options 3D launch文件的配置
textfile="$(find cartographer_ros)/urdf/myself_robot.urdf" /> type="robot_state_publisher" /> type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename myself_rslidar_3d.lua" output="screen"> type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" /> 3D pure location lua文件的配置 include "myself_rslidar_3d.lua" TRAJECTORY_BUILDER.pure_localization = true POSE_GRAPH.optimize_every_n_nodes = 100 return options 3D pure location launch文件的配置
textfile="$(find cartographer_ros)/urdf/myself_robot.urdf" /> type="robot_state_publisher" /> type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename myself_backpack_3d_localization.lua -load_state_filename $(arg load_state_filename)" output="screen"> type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" /> Assets writer 3D lua文件的配置 VOXEL_SIZE = 5e-2 include "transform.lua" options = { tracking_frame = "imu", #imu坐标系 pipeline = { { action = "min_max_range_filter", min_range = 1., max_range = 20., }, { action = "dump_num_points", }, { action = "fixed_ratio_sampler", sampling_ratio = 0.01, }, { action = "write_ply", filename = "points.ply" }, -- Gray X-Rays. These only use geometry to color pixels. -- Now we recolor our points by frame and write another batch of X-Rays. It -- is visible in them what was seen by the horizontal and the vertical -- laser. { action = "color_points", frame_id = "rslidar",#雷达坐标系 color = { 255., 0., 0. }, }, { action = "write_xray_image", voxel_size = VOXEL_SIZE, filename = "xray_xy_all_color", transform = XY_TRANSFORM, }, } } return options Assets writer 3D launch文件的配置 type="cartographer_assets_writer" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename assets_writer_myself_3d.lua -urdf_filename $(find cartographer_ros)/urdf/myself_robot.urdf -bag_filenames $(arg bag_filenames) -pose_graph_filename $(arg pose_graph_filename)" output="screen"> #SLAM 启动雷达点云 $>> roslaunch rslidar_pointcloud cloud_nodelet.launch 启动Cartographer建图 $>> roslaunch cartographer_ros myself_rslidar_2d.launch Or $>> roslaunch cartographer_ros myself_rslidar_3d.launch Tips:纯定位需要修改源码,所以如果建图前请确保,src/cartographer_ros/cartographer_ros/cartographer_ros/occupancy_grid_node.main.cc中main函数上面第五行是否注释了 occupancy_grid_publisher_.publish(*msg); 纯定位注释掉,建图时打开,然后执行catkin_make,再执行建图或者定位。 3d建图需要先发布imu ,并且需要rosbag保存点云和imu消息: $>> rosrun imu_pub imu_pub_node $>> rosbag record /imu /rslidar_points 结束建图 $>> rosservice call /finish_trajectory 0 保存地图,在~/.ros目录下 $>> rosservice call /write_state “filenames: ’map.pbstream’” 拷贝出地图转化地图到ros使用的栅格地图yaml文件,使用绝对路径 $>> rosrun cartographer_ros cartographer_pbstream_to_ros_map -bpstream_filename path_of_pbstream/map.pbstream 3d点云地图转化与查看 地图格式Bag转ply $>> roslaunch cartographer_ros assert_writer_myself_3d.launch bag_filenames:=~/bag_path/2020.....bag.bag pose_graph_filename:=~/pbstream_path/map.pbstream 地图格式Ply转pcd $>> pcl_ply2pcd your.bag_points.ply your_pcd_filename.pcd 查看点云 $>> pcl_viewer your_pcd_filename.pcd 如果效果不好,使用offline_myself_rslidar_3d.launch重新建图,记得更改launch加载的bag文件路径,如果不满意,修改myself_rslidar_3d.lua文件的TRAJECTORY_BUILD_3D.max_range的大小,建议区间在30-80,之至点云图满意收敛。 命令: $>> roslaunch cartographe_ros myself_backpack_2(3)d_localization.launch 根据实际情况加载load_state_filename,如果未显示rviz,请查看launch文件是否注释了rviz的显示。 安装导航功能包 $>> sudo apt-get install ros-kinect-navigation 导航包主要是launch文件加cost_map、planner参数配置文件。 launch文件的配置 move_base_params.yaml文件参数 # Move base node parameters. For full documentation of the parameters in this file, please see # # http://www.ros.org/wiki/move_base # #启用costmap shutdown_costmaps: false #设置控制频率 controller_frequency: 5.0 controller_patience: 3.0 planner_frequency: 1.0 planner_patience: 5.0 oscillation_timeout: 10.0 oscillation_distance: 0.2 #选择使用dwa local planner和navfn global planner # local planner - default is trajectory rollout base_local_planner: "dwa_local_planner/DWAPlannerROS" base_global_planner: "navfn/NavfnROS" #alternatives: global_planner/GlobalPlanner, carrot_planner/CarrotPlanner #这里定义恢复行为,当机器人震荡时,会按顺序进行恢复行为,清除障碍物,这里注释了使用默认的恢复行为。 #We plan to integrate recovery behaviors for turtlebot but currently those belong to gopher and still have to be adapted. ## recovery behaviors; we avoid spinning, but we need a fall-back replanning #recovery_behavior_enabled: true #recovery_behaviors: #- name: 'super_conservative_reset1' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'conservative_reset1' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'aggressive_reset1' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'clearing_rotation1' #type: 'rotate_recovery/RotateRecovery' #- name: 'super_conservative_reset2' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'conservative_reset2' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'aggressive_reset2' #type: 'clear_costmap_recovery/ClearCostmapRecovery' #- name: 'clearing_rotation2' #type: 'rotate_recovery/RotateRecovery' #super_conservative_reset1: #reset_distance: 3.0 #conservative_reset1: #reset_distance: 1.5 #aggressive_reset1: #reset_distance: 0.0 #super_conservative_reset2: #reset_distance: 3.0 #conservative_reset2: #reset_distance: 1.5 #aggressive_reset2: #reset_distance: 0.0 costmap_common_params.yaml文件参数 max_obstacle_height: 1.40 # assume something like an arm is mounted on top of the robot # Obstacle Cost Shaping (http://wiki.ros.org/costmap_2d/hydro/inflation) #设置机器人半径或者底盘轮廓四个点 robot_radius: 0.25 # distance a circular robot should be clear of the obstacle (kobuki: 0.18) # footprint: [[x0, y0], [x1, y1], ... [xn, yn]] # if the robot is not circular map_type: voxel voxel_layer: enabled: true max_obstacle_height: 2.2 origin_z: 0.0 z_resolution: 0.1 z_voxels: 22 unknown_threshold: 15 mark_threshold: 0 combination_method: 1 track_unknown_space: true #true needed for disabling global path planning through unknown space obstacle_range: 2.5 raytrace_range: 3.0 publish_voxel_map: true observation_sources: bump #camera scan bump #设置检测障碍物的信息源 # scan: # data_type: LaserScan # topic: scan # marking: true # clearing: true # min_obstacle_height: 0.1 # max_obstacle_height: 0.3 # camera: # data_type: PointCloud2 # topic: camera/depth/points # marking: true # clearing: true # min_obstacle_height: 0.0 # max_obstacle_height: 2.0 bump: data_type: PointCloud2 #信息源的类型 topic: /rslidar_points #信息源话题 marking: true clearing: true min_obstacle_height: 0.0 max_obstacle_height: 0.15 #cost_scaling_factor and inflation_radius were now moved to the inflation_layer ns inflation_layer: enabled: true cost_scaling_factor: 2.58 # exponential rate at which the obstacle cost drops off (default: 10) #设置障碍物膨胀半径 inflation_radius: 0.5 # max. distance from an obstacle at which costs are incurred for planning paths. static_layer: enabled: true local_costmap_params.yaml 文件参数 local_costmap: global_frame: odom #/map robot_base_frame: base_link update_frequency: 3.0 #5.0 publish_frequency: 2.0 static_map: false #false #局部cost_map采用滑动窗口,进行膨胀 rolling_window: true width: 4.0 height: 4.0 resolution: 0.05 origin_x: 5.0 origin_y: 0 transform_tolerance: 0.5 plugins: - {name: voxel_layer, type: "costmap_2d::VoxelLayer"} - {name: inflation_layer, type: "costmap_2d::InflationLayer"} global_costmap_params.yaml文件参数 global_costmap: global_frame: map robot_base_frame: base_link update_frequency: 2.0 publish_frequency: 0.5 static_map: true rolling_window: false transform_tolerance: 0.5 plugins: - {name: static_layer, type: "costmap_2d::StaticLayer"} - {name: voxel_layer, type: "costmap_2d::VoxelLayer"} - {name: inflation_layer, type: "costmap_2d::InflationLayer"} dwa_local_planner_params.yaml文件参数 DWAPlannerROS: #设置机器人的速度和旋转速度 # Robot Configuration Parameters max_vel_x: 0.5 min_vel_x: 0.0 max_vel_y: 0.0 min_vel_y: 0.0 # The velocity when robot is moving in a straight line max_trans_vel: 0.55 min_trans_vel: 0.1 trans_stopped_vel: 0.1 max_rot_vel: 5.0 min_rot_vel: 0.8 rot_stopped_vel: 0.8 acc_lim_x: 1.0 acc_lim_theta: 2.0 acc_lim_y: 0.0 #目标点误差,如果过小会导致机器人在目标点震荡 单位为米和弧度 # Goal Tolerance Parametes yaw_goal_tolerance: 0.3 xy_goal_tolerance: 0.15 # latch_xy_goal_tolerance: false # Forward Simulation Parameters sim_time: 4.0 vx_samples: 20 vy_samples: 0 vtheta_samples: 40 # Trajectory Scoring Parameters path_distance_bias: 32.0 goal_distance_bias: 24.0 occdist_scale: 0.1 forward_point_distance: 0.325 stop_time_buffer: 0.2 scaling_speed: 0.25 max_scaling_factor: 0.2 # Oscillation Prevention Parameters oscillation_reset_dist: 0.05 # Debugging publish_traj_pc : true publish_cost_grid_pc: true global_frame_id: odom navfn_global_planner_params.yaml文件参数 NavfnROS: visualize_potential: false #Publish potential for rviz as pointcloud2, not really helpful, default false allow_unknown: true #Specifies whether or not to allow navfn to create plans that traverse unknown space, default true #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work planner_window_x: 0.0 #Specifies the x size of an optional window to restrict the planner to, default 0.0 planner_window_y: 0.0 #Specifies the y size of an optional window to restrict the planner to, default 0.0 default_tolerance: 0.0 #If the goal is in an obstacle, the planer will plan to the nearest point in the radius of default_tolerance, default 0.0 #The area is always searched, so could be slow for big values 采用Cartographer定位和navegation stack中的move_base导航。 命令: $>> roslaunch rslidar_pointcloud cloud_nodelet.launch $>> roslaunch cartographe_ros myself_backpack_2d_localization.launch $>> roslaunch navigation zky_move_base.launch $>> rosrun cmd_to_stm cmd_to_stm 然后使用RVIZ中的2D navigation goal 选择图中的一点,可以在终端 rostopic echo /simple/goal 查看。选中的点是相对机器人坐标,非全局坐标。下面的设置自定义导航点时需要注意。 规定好路径点和达到目标点时的位姿,输入在源代码的数组中,前三位表示xyz的平移,后四位表示到达目标点时的位姿,0 0 0 1,表示不改变方向,0 0 1 0,表示180°方向,0 0 0.707 0.707 表示90°,0 0 -0.707 0.707表示270°,逆时针方向为正。 规划好目标点,程序依次喂入目标点,实现路线规划导航。 在导航命令基础上运行,命令: $>> rosrun simple_navigation_goal simple_navigation_goal 启动雷达和建图 $>> roslaunch rslidar_pointcloud cloud_nodelet.launch 启动建图, (Cartographer存在问题,如何发步ros格式的map)暂时以hector SLAM作为建图 $>> roslaunch pointcloud_to_laserscan point_to_scan.launch $>> roslaunch navigation hector.launch 启动导航 $>> roslaunch navigation zky_move_base.launch $>> rosrun cmd_to_stm cmd_to_stm 启动目标点(更改目标点列表元素,适应场景) $>> rosrun navigation explor_slam.py 根据imu通讯协议,读取imu的xyz加速度和四元数,发布/imu消息。 根据编码器数据或cmd_vel发布/odom $>> rosrun cmd_vel_to_stm cmd_to_stm 程序通过监听/cmd_vel话题,将速度信息发送给下位机 $>> rosrun cmd_vel_to_stm robot_teleop.py 程序通过键盘发布cmd_vel,配合上面的对机器人进行键盘遥控。 参数设置请参照wiki.ros.org/pointcloud_to_laserscan $>> roslaunch pointcloud_to_laserscan point_to_scan.launch 其中重映射了cloud_in->rslidar_points 发布/scan话题 ROS移动机器人基于RRT(快速探索随机树)算法 rrt_exploration实现真实机器人自主探索建图: https://blog.csdn.net/qq_42145185/article/details/82461072 PIBOT导航机器人: https://www.jianshu.com/u/7f508db63608