GLIM
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Public Attributes | List of all members
glim::EstimationFrame Struct Reference

Odometry estimation frame. More...

#include <estimation_frame.hpp>

Public Types

using Ptr = std::shared_ptr< EstimationFrame >
 
using ConstPtr = std::shared_ptr< const EstimationFrame >
 

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW EstimationFrame::Ptr clone () const
 Make a clone of the estimation frame. (Points data are shallow copied)
 
EstimationFrame::Ptr clone_wo_points () const
 Make a clone of the estimation frame instance but without points data.
 
const Eigen::Isometry3d T_world_sensor () const
 Get the sensor pose according to frame_id.
 
void set_T_world_sensor (FrameID frame_id, const Eigen::Isometry3d &T)
 Set the sensor pose.
 
template<typename T >
T * get_custom_data (const std::string &key)
 Get the custom data and cast it to the specified type.
 
template<typename T >
const T * get_custom_data (const std::string &key) const
 Get the custom data and cast it to the specified type.
 

Public Attributes

long id
 Frame ID.
 
double stamp
 Timestamp.
 
Eigen::Isometry3d T_lidar_imu
 LiDAR-IMU transformation.
 
Eigen::Isometry3d T_world_lidar
 LiDAR pose in the world space.
 
Eigen::Isometry3d T_world_imu
 IMU pose in the world space.
 
Eigen::Vector3d v_world_imu
 IMU velocity in the world frame.
 
Eigen::Matrix< double, 6, 1 > imu_bias
 IMU bias.
 
PreprocessedFrame::ConstPtr raw_frame
 Raw input point cloud (LiDAR frame)
 
Eigen::Matrix< double, 8, -1 > imu_rate_trajectory
 IMU-rate trajectory 8 x N [t, x, y, z, qx, qy, qz, qw].
 
FrameID frame_id
 Coordinate frame of $frame.
 
gtsam_points::PointCloud::ConstPtr frame
 Deskewed points for state estimation.
 
std::vector< gtsam_points::GaussianVoxelMap::Ptr > voxelmaps
 Multi-resolution voxelmaps.
 
std::unordered_map< std::string, std::shared_ptr< void > > custom_data
 User-defined custom data.
 

Detailed Description

Odometry estimation frame.

Member Function Documentation

◆ clone()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW EstimationFrame::Ptr glim::EstimationFrame::clone ( ) const

Make a clone of the estimation frame. (Points data are shallow copied)

Returns
EstimationFrame::Ptr Cloned frame

◆ clone_wo_points()

EstimationFrame::Ptr glim::EstimationFrame::clone_wo_points ( ) const

Make a clone of the estimation frame instance but without points data.

Returns
EstimationFrame::Ptr Cloned frame without points

◆ get_custom_data() [1/2]

template<typename T >
T * glim::EstimationFrame::get_custom_data ( const std::string &  key)
inline

Get the custom data and cast it to the specified type.

Note
This method does not check the type of the custom data.
Parameters
keyKey of the custom data
Returns
T* Pointer to the custom data. nullptr if not found.

◆ get_custom_data() [2/2]

template<typename T >
const T * glim::EstimationFrame::get_custom_data ( const std::string &  key) const
inline

Get the custom data and cast it to the specified type.

Note
This method does not check the type of the custom data.
Parameters
keyKey of the custom data
Returns
T* Pointer to the custom data. nullptr if not found.

◆ set_T_world_sensor()

void glim::EstimationFrame::set_T_world_sensor ( FrameID  frame_id,
const Eigen::Isometry3d &  T 
)

Set the sensor pose.

Parameters
frame_idSensor coodinate frame
TSensor pose

◆ T_world_sensor()

const Eigen::Isometry3d glim::EstimationFrame::T_world_sensor ( ) const

Get the sensor pose according to frame_id.

Returns
const Eigen::Isometry3d Sensor pose

The documentation for this struct was generated from the following file: