BsplineSE3.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_CORE_BSPLINESE3_H
23 #define OV_CORE_BSPLINESE3_H
24 
25 #include <Eigen/Eigen>
26 #include <map>
27 #include <vector>
28 
29 #include "utils/print.h"
30 #include "utils/quat_ops.h"
31 
32 namespace ov_core {
33 
104 class BsplineSE3 {
105 
106 public:
111 
120  void feed_trajectory(std::vector<Eigen::VectorXd> traj_points);
121 
129  bool get_pose(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG);
130 
140  bool get_velocity(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG, Eigen::Vector3d &w_IinI, Eigen::Vector3d &v_IinG);
141 
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);
155 
157  double get_start_time() { return timestamp_start; }
158 
159 protected:
161  double dt;
162 
165 
167  typedef std::map<double, Eigen::Matrix4d, std::less<double>, Eigen::aligned_allocator<std::pair<const double, Eigen::Matrix4d>>>
169 
172 
187  static bool find_bounding_poses(const double timestamp, const AlignedEigenMat4d &poses, double &t0, Eigen::Matrix4d &pose0, double &t1,
188  Eigen::Matrix4d &pose1);
189 
205  static bool find_bounding_control_points(const double timestamp, const AlignedEigenMat4d &poses, double &t0, Eigen::Matrix4d &pose0,
206  double &t1, Eigen::Matrix4d &pose1, double &t2, Eigen::Matrix4d &pose2, double &t3,
207  Eigen::Matrix4d &pose3);
208 };
209 
210 } // namespace ov_core
211 
212 #endif // OV_CORE_BSPLINESE3_H
ov_core::BsplineSE3::control_points
AlignedEigenMat4d control_points
Our control SE3 control poses (R_ItoG, p_IinG)
Definition: BsplineSE3.h:171
ov_core::BsplineSE3::feed_trajectory
void feed_trajectory(std::vector< Eigen::VectorXd > traj_points)
Will feed in a series of poses that we will then convert into control points.
Definition: BsplineSE3.cpp:26
ov_core::BsplineSE3::AlignedEigenMat4d
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...
Definition: BsplineSE3.h:168
ov_core::BsplineSE3::timestamp_start
double timestamp_start
Start time of the system.
Definition: BsplineSE3.h:164
ov_core::BsplineSE3::get_velocity
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.
Definition: BsplineSE3.cpp:127
ov_core::BsplineSE3::get_acceleration
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.
Definition: BsplineSE3.cpp:180
ov_core::BsplineSE3::get_pose
bool get_pose(double timestamp, Eigen::Matrix3d &R_GtoI, Eigen::Vector3d &p_IinG)
Gets the orientation and position at a given timestamp.
Definition: BsplineSE3.cpp:92
print.h
ov_core::BsplineSE3::find_bounding_poses
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.
Definition: BsplineSE3.cpp:249
ov_core::BsplineSE3::get_start_time
double get_start_time()
Returns the simulation start time that we should start simulating from.
Definition: BsplineSE3.h:157
ov_core::BsplineSE3::find_bounding_control_points
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.
Definition: BsplineSE3.cpp:301
quat_ops.h
ov_core::BsplineSE3
B-Spline which performs interpolation over SE(3) manifold.
Definition: BsplineSE3.h:104
ov_core::BsplineSE3::dt
double dt
Uniform sampling time for our control points.
Definition: BsplineSE3.h:161
ov_core::BsplineSE3::BsplineSE3
BsplineSE3()
Default constructor.
Definition: BsplineSE3.h:110
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17