Continuous trajectory class for offline batch optimization.
More...
#include <continuous_trajectory.hpp>
|
| | ContinuousTrajectory (char symbol, double start_time, double end_time, double knot_interval) |
| | Construct a continuous trajectory instance.
|
| |
|
double | knot_stamp (int i) const |
| | Time of a spline knot.
|
| |
|
int | knot_id (double t) const |
| | Key knot ID for a given time.
|
| |
|
int | knot_max_id () const |
| | Number of spline knots.
|
| |
| gtsam::Pose3_ | pose (double t, const gtsam::Double_ &t_) |
| | Get an expression of the interpolated time at t.
|
| |
| gtsam::Pose3 | pose (const gtsam::Values &values, double t) |
| | Calculate the interpolated time at t.
|
| |
| gtsam::Vector6_ | imu (double t, const gtsam::Double_ &t_, const Eigen::Vector3d &g=Eigen::Vector3d(0.0, 0.0, 9.80665)) |
| | Get an expression of the linear acceleration and angular velocity at t.
|
| |
| gtsam::Vector6 | imu (const gtsam::Values &values, double t, const Eigen::Vector3d &g=Eigen::Vector3d(0.0, 0.0, 9.80665)) |
| | Calculate the linear acceleration and angular velocity at t.
|
| |
| gtsam::Values | fit_knots (const std::vector< double > &stamps, const std::vector< gtsam::Pose3 > &poses, double smoothness, const gtsam::LevenbergMarquardtParams &lm_params) const |
| | Optimize spline knots to fit the interpolated trajectory to a set of poses.
|
| |
|
gtsam::Values | fit_knots (const std::vector< double > &stamps, const std::vector< gtsam::Pose3 > &poses, double smoothness=1e-3, bool verbose=false) const |
| |
|
|
const char | symbol |
| |
|
const double | start_time |
| |
|
const double | end_time |
| |
|
const double | knot_interval |
| |
Continuous trajectory class for offline batch optimization.
◆ ContinuousTrajectory()
| gtsam_points::ContinuousTrajectory::ContinuousTrajectory |
( |
char |
symbol, |
|
|
double |
start_time, |
|
|
double |
end_time, |
|
|
double |
knot_interval |
|
) |
| |
Construct a continuous trajectory instance.
- Parameters
-
| symbol | Key symbol |
| start_time | Start time of the trajectory |
| end_time | End time of the trajectory |
| knot_interval | Time interval of spline control knots |
◆ fit_knots()
| gtsam::Values gtsam_points::ContinuousTrajectory::fit_knots |
( |
const std::vector< double > & |
stamps, |
|
|
const std::vector< gtsam::Pose3 > & |
poses, |
|
|
double |
smoothness, |
|
|
const gtsam::LevenbergMarquardtParams & |
lm_params |
|
) |
| const |
Optimize spline knots to fit the interpolated trajectory to a set of poses.
- Parameters
-
| stamps | Timestamps of target poses |
| poses | Target poses |
| smoothness | Smoothness regularization to prevent underconstrained system (If smoothness <= 0.0, regularization will be disabled) |
- Returns
- Knots of B-spline fitted to the target poses
◆ imu() [1/2]
| gtsam::Vector6 gtsam_points::ContinuousTrajectory::imu |
( |
const gtsam::Values & |
values, |
|
|
double |
t, |
|
|
const Eigen::Vector3d & |
g = Eigen::Vector3d(0.0, 0.0, 9.80665) |
|
) |
| |
Calculate the linear acceleration and angular velocity at t.
- Parameters
-
| values | Values including knot poses |
| t | Time |
◆ imu() [2/2]
| gtsam::Vector6_ gtsam_points::ContinuousTrajectory::imu |
( |
double |
t, |
|
|
const gtsam::Double_ & |
t_, |
|
|
const Eigen::Vector3d & |
g = Eigen::Vector3d(0.0, 0.0, 9.80665) |
|
) |
| |
Get an expression of the linear acceleration and angular velocity at t.
- Parameters
-
◆ pose() [1/2]
| gtsam::Pose3 gtsam_points::ContinuousTrajectory::pose |
( |
const gtsam::Values & |
values, |
|
|
double |
t |
|
) |
| |
Calculate the interpolated time at t.
- Parameters
-
| values | Values including knot poses |
| t | Time |
◆ pose() [2/2]
| gtsam::Pose3_ gtsam_points::ContinuousTrajectory::pose |
( |
double |
t, |
|
|
const gtsam::Double_ & |
t_ |
|
) |
| |
Get an expression of the interpolated time at t.
- Parameters
-
The documentation for this class was generated from the following file: