mirror of
https://github.com/MAPIRlab/rf2o_laser_odometry.git
synced 2023-04-06 19:28:55 +08:00
add getIncrementCovariance & rm return by ref getIncrement
This commit is contained in:
@@ -67,9 +67,10 @@ public:
|
|||||||
|
|
||||||
void setLaserPose(const mrpt::poses::CPose3D& laser_pose);
|
void setLaserPose(const mrpt::poses::CPose3D& laser_pose);
|
||||||
|
|
||||||
mrpt::poses::CPose3D& getIncrement();
|
|
||||||
const mrpt::poses::CPose3D& getIncrement() const;
|
const mrpt::poses::CPose3D& getIncrement() const;
|
||||||
|
|
||||||
|
const Eigen::Matrix<float, 3, 3>& getIncrementCovariance() const;
|
||||||
|
|
||||||
mrpt::poses::CPose3D& getPose();
|
mrpt::poses::CPose3D& getPose();
|
||||||
const mrpt::poses::CPose3D& getPose() const;
|
const mrpt::poses::CPose3D& getPose() const;
|
||||||
|
|
||||||
|
|||||||
@@ -158,15 +158,14 @@ void CLaserOdometry2D::Init(const sensor_msgs::LaserScan& scan,
|
|||||||
last_odom_time = ros::Time::now();
|
last_odom_time = ros::Time::now();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const mrpt::poses::CPose3D& CLaserOdometry2D::getIncrement() const
|
||||||
mrpt::poses::CPose3D& CLaserOdometry2D::getIncrement()
|
|
||||||
{
|
{
|
||||||
return last_increment;
|
return last_increment;
|
||||||
}
|
}
|
||||||
|
|
||||||
const mrpt::poses::CPose3D& CLaserOdometry2D::getIncrement() const
|
const Eigen::Matrix<float, 3, 3>& CLaserOdometry2D::getIncrementCovariance() const
|
||||||
{
|
{
|
||||||
return last_increment;
|
return cov_odo;
|
||||||
}
|
}
|
||||||
|
|
||||||
mrpt::poses::CPose3D& CLaserOdometry2D::getPose()
|
mrpt::poses::CPose3D& CLaserOdometry2D::getPose()
|
||||||
|
|||||||
Reference in New Issue
Block a user