gtsam_points
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
gtsam_points::ContinuousTrajectory Class Reference

Continuous trajectory class for offline batch optimization. More...

#include <continuous_trajectory.hpp>

Public Member Functions

 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
 

Public Attributes

const char symbol
 
const double start_time
 
const double end_time
 
const double knot_interval
 

Detailed Description

Continuous trajectory class for offline batch optimization.

Constructor & Destructor Documentation

◆ ContinuousTrajectory()

gtsam_points::ContinuousTrajectory::ContinuousTrajectory ( char  symbol,
double  start_time,
double  end_time,
double  knot_interval 
)

Construct a continuous trajectory instance.

Parameters
symbolKey symbol
start_timeStart time of the trajectory
end_timeEnd time of the trajectory
knot_intervalTime interval of spline control knots

Member Function Documentation

◆ 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
stampsTimestamps of target poses
posesTarget poses
smoothnessSmoothness 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
valuesValues including knot poses
tTime

◆ 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
tTime
t_Expression of t

◆ pose() [1/2]

gtsam::Pose3 gtsam_points::ContinuousTrajectory::pose ( const gtsam::Values &  values,
double  t 
)

Calculate the interpolated time at t.

Parameters
valuesValues including knot poses
tTime

◆ 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
tTime
t_Expression of t

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