Go to the documentation of this file.
22 #ifndef OV_CORE_BSPLINESE3_H
23 #define OV_CORE_BSPLINESE3_H
25 #include <Eigen/Eigen>
129 bool get_pose(
double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG);
140 bool get_velocity(
double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG, Eigen::Vector3d &w_IinI, Eigen::Vector3d &v_IinG);
153 bool get_acceleration(
double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG, Eigen::Vector3d &w_IinI,
154 Eigen::Vector3d &v_IinG, Eigen::Vector3d &alpha_IinI, Eigen::Vector3d &a_IinG);
167 typedef std::map<double, Eigen::Matrix4d, std::less<double>, Eigen::aligned_allocator<std::pair<const double, Eigen::Matrix4d>>>
188 Eigen::Matrix4d &pose1);
206 double &t1, Eigen::Matrix4d &pose1,
double &t2, Eigen::Matrix4d &pose2,
double &t3,
207 Eigen::Matrix4d &pose3);
212 #endif // OV_CORE_BSPLINESE3_H
AlignedEigenMat4d control_points
Our control SE3 control poses (R_ItoG, p_IinG)
void feed_trajectory(std::vector< Eigen::VectorXd > traj_points)
Will feed in a series of poses that we will then convert into control points.
std::map< double, Eigen::Matrix4d, std::less< double >, Eigen::aligned_allocator< std::pair< const double, Eigen::Matrix4d > > > AlignedEigenMat4d
Type defintion of our aligned eigen4d matrix: https://eigen.tuxfamily.org/dox/group__TopicStlContaine...
double timestamp_start
Start time of the system.
bool get_velocity(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG, Eigen::Vector3d &w_IinI, Eigen::Vector3d &v_IinG)
Gets the angular and linear velocity at a given timestamp.
bool get_acceleration(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG, Eigen::Vector3d &w_IinI, Eigen::Vector3d &v_IinG, Eigen::Vector3d &alpha_IinI, Eigen::Vector3d &a_IinG)
Gets the angular and linear acceleration at a given timestamp.
bool get_pose(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG)
Gets the orientation and position at a given timestamp.
static bool find_bounding_poses(const double timestamp, const AlignedEigenMat4d &poses, double &t0, Eigen::Matrix4d &pose0, double &t1, Eigen::Matrix4d &pose1)
Will find the two bounding poses for a given timestamp.
double get_start_time()
Returns the simulation start time that we should start simulating from.
static bool find_bounding_control_points(const double timestamp, const AlignedEigenMat4d &poses, double &t0, Eigen::Matrix4d &pose0, double &t1, Eigen::Matrix4d &pose1, double &t2, Eigen::Matrix4d &pose2, double &t3, Eigen::Matrix4d &pose3)
Will find two older poses and two newer poses for the current timestamp.
B-Spline which performs interpolation over SE(3) manifold.
double dt
Uniform sampling time for our control points.
BsplineSE3()
Default constructor.
Core algorithms for OpenVINS.
ov_core
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17