mirror of
https://github.com/MAPIRlab/rf2o_laser_odometry.git
synced 2023-04-06 19:28:55 +08:00
add func get Pose/Increment
This commit is contained in:
committed by
Jeremie Deray
parent
241358540a
commit
c3d22b8780
@@ -79,6 +79,12 @@ protected:
|
||||
|
||||
void setLaserPose(const tf::Transform& laser_pose);
|
||||
|
||||
mrpt::poses::CPose3D& getIncrement();
|
||||
const mrpt::poses::CPose3D& getIncrement() const;
|
||||
|
||||
mrpt::poses::CPose3D& getPose();
|
||||
const mrpt::poses::CPose3D& getPose() const;
|
||||
|
||||
protected:
|
||||
|
||||
bool module_initialized,first_laser_scan;
|
||||
@@ -137,6 +143,8 @@ protected:
|
||||
mrpt::math::CMatrixFloat31 kai_loc_old;
|
||||
mrpt::math::CMatrixFloat31 kai_loc_level;
|
||||
|
||||
mrpt::poses::CPose3D last_increment;
|
||||
|
||||
mrpt::poses::CPose3D laser_pose_on_robot;
|
||||
mrpt::poses::CPose3D laser_pose_on_robot_inv;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user