Skip to content

Commit

Permalink
20210125
Browse files Browse the repository at this point in the history
  • Loading branch information
narutojxl committed Jan 25, 2021
1 parent c9b8dfa commit ac27043
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 10 deletions.
12 changes: 6 additions & 6 deletions estimator/config/jxl_config_handheld.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,21 @@ segment_theta: 0.53 # Lego-loam: 1.0
# laser parameters
idx_ref: 0 #主雷达id
n_scans: 16 #laser beams
num_of_laser: 2
num_of_laser: 1 #default

cloud_topic:
- "/left/velodyne_points"
- "/right/velodyne_points"
#- "/left/velodyne_points"
#- "/right/velodyne_points"
- "/velodyne_points"

# window sizes
window_size: 4
opt_window_size: 2


############################## For normal use
# Extrinsic parameter between multiple LiDARs.
#代码中当需要对外参提纯或者估计外参时,不对点云进行分割
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# Extrinsic parameter between multiple LiDARs.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Have no prior about extrinsic parameters. We will initialize and optimize around them

Expand Down
2 changes: 1 addition & 1 deletion estimator/src/lidarMapper/lidar_mapper_keyframe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ std::vector<PointICovCloud::Ptr> corner_cloud_keyframes_cov;//所有keyframes co
std::vector<PointICovCloud::Ptr> outlier_cloud_keyframes_cov;//所有keyframes outlier points

// downsampling voxel grid
pcl::VoxelGridCovarianceMLOAM<PointI> down_size_filter_surf;
pcl::VoxelGridCovarianceMLOAM<PointI> down_size_filter_surf; //见mloam_pcl package
pcl::VoxelGridCovarianceMLOAM<PointI> down_size_filter_corner;
pcl::VoxelGridCovarianceMLOAM<PointI> down_size_filter_outlier;
pcl::VoxelGridCovarianceMLOAM<PointI> down_size_filter_surrounding_keyframes;
Expand Down
9 changes: 6 additions & 3 deletions estimator/src/utility/visualization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ void pubOdometry(Estimator &estimator, const double &time)
laser_odom.pose.pose.position.y = pose_laser_cur.t_.y();
laser_odom.pose.pose.position.z = pose_laser_cur.t_.z();
v_pub_laser_odom[n].publish(laser_odom);
publishTF(laser_odom);
publishTF(laser_odom);

geometry_msgs::PoseStamped laser_pose;
laser_pose.header = laser_odom.header;
Expand Down Expand Up @@ -224,7 +224,8 @@ void pubOdometry(Estimator &estimator, const double &time)
extrinsics.header.frame_id = "/laser_" + std::to_string(IDX_REF);
extrinsics.status = ESTIMATE_EXTRINSIC;
for (size_t n = 0; n < NUM_OF_LASER; n++)
{
{
// if(n == IDX_REF) continue;
nav_msgs::Odometry exts;
exts.header.seq = n;
exts.header.stamp = ros::Time(time);
Expand All @@ -240,7 +241,9 @@ void pubOdometry(Estimator &estimator, const double &time)
for (size_t i = 0; i < 6; i++)
for (size_t j = 0; j < 6; j++)
exts.pose.covariance[i * 6 + j] = float(estimator.covbl_[n](i, j));
publishTF(exts);

if(n != IDX_REF) //jxl add: do not publish主雷达到主雷达的tf
publishTF(exts);
extrinsics.odoms.push_back(exts);
}
pub_extrinsics.publish(extrinsics); //外参topic "/extrinsics"
Expand Down

0 comments on commit ac27043

Please sign in to comment.