Skip to content

Commit 62833e8

Browse files
authored
Merge pull request #82 from malban/build-fixes
Build fixes for ros1
2 parents 3f80919 + b352c8e commit 62833e8

1 file changed

Lines changed: 2 additions & 2 deletions

File tree

laser_scan_matcher/src/laser_scan_matcher.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -522,7 +522,7 @@ void LaserScanMatcher::processScan(LDP& curr_ldp_scan, const ros::Time& time)
522522
yaw_cov = gsl_matrix_get(output_.cov_x_m, 2, 2);
523523

524524
// rotate xy covariance from the keyframe into odom frame
525-
auto rotation = getLaserRotation(f2b_kf_);
525+
auto rotation = getLaserRotation(keyframe_base_in_fixed_);
526526
xy_cov = rotation * xy_cov * rotation.transpose();
527527
}
528528
else {
@@ -859,7 +859,7 @@ void LaserScanMatcher::createTfFromXYTheta(
859859
}
860860

861861
Eigen::Matrix2f LaserScanMatcher::getLaserRotation(const tf::Transform& odom_pose) const {
862-
tf::Transform laser_in_fixed = odom_pose * laser_to_base_;
862+
tf::Transform laser_in_fixed = odom_pose * laser_from_base_;
863863
tf::Matrix3x3 fixed_from_laser_rot(laser_in_fixed.getRotation());
864864
double r,p,y;
865865
fixed_from_laser_rot.getRPY(r, p, y);

0 commit comments

Comments
 (0)