Struct KeyFrame

Struct Documentation

struct KeyFrame

KeyFrame (pose node)

Public Types

using PointT = pcl::PointXYZI
using PointNormal = pcl::PointXYZRGBNormal
using Ptr = std::shared_ptr<KeyFrame>

Public Functions

KeyFrame(const rclcpp::Time &stamp, const Eigen::Isometry3d &odom, double accum_distance, const pcl::PointCloud<PointT>::ConstPtr &cloud)

Constructor for class KeyFrame.

Parameters:
  • stamp

  • odom

  • accum_distance

  • cloud

Returns:

KeyFrame(const std::string &directory, g2o::HyperGraph *graph)

Constructor for class KeyFrame.

Parameters:
  • directory

  • graph

virtual ~KeyFrame()
void save(const std::string &directory)

Saves the keyframe into a given directory.

Parameters:

directory

bool load(const std::string &directory, g2o::HyperGraph *graph)

Loads the keyframes from a directory into the graph pointer.

Parameters:
  • directory

  • graph

Returns:

Success or failure

long id() const
Returns:

Eigen::Isometry3d estimate() const
Returns:

Public Members

rclcpp::Time stamp
Eigen::Isometry3d odom
double accum_distance
pcl::PointCloud<PointT>::ConstPtr cloud
pcl::PointCloud<PointNormal>::Ptr cloud_seg_body
std::vector<int> x_plane_ids
std::vector<int> y_plane_ids
std::vector<int> hort_plane_ids
boost::optional<Eigen::Vector4d> floor_coeffs
boost::optional<Eigen::Vector3d> utm_coord
boost::optional<Eigen::Vector3d> acceleration
boost::optional<Eigen::Quaterniond> orientation
g2o::VertexSE3 *node