Trajectories¶
All trajectories inherit the methods and attributes from this base class. Note that the base class is not exported and can thus not be used.
-
class
kontiki.trajectories.
Trajectory
¶ -
position
(t : float) → ndarray¶ Position (3D vector) at time t
-
velocity
(t : float) → ndarray¶ Velocity (3D vector) at time t
-
acceleration
(t : float) → ndarray¶ Acceleration (3D vector) at time t
-
orientation
(t : float) → ndarray¶ Orientation (unit quaternion) at time t
-
angular_velocity
(t : float) → ndarray¶ The angular velocity at time t
-
from_world
(X : ndarray) → ndarray¶ Transform a 3D point from the world coordinate frame to the trajectory coordinate frame.
-
to_world
(X : ndarray) → ndarray¶ Transform a 3D point from the trajectory to the world coordinate frame.
-
clone
() → Trajectory¶ Clone the trajectory
-
min_time
¶ Minimum time (including) that the trajectory is valid
-
max_time
¶ Maximum time (excluding) that the trajectory is valid
-
locked
¶ If True then the trajectory is unchanged during estimation
-
Splined trajectories¶
The splined trajectories are cubic B-splines, defined as in [Qin2000].
-
class
kontiki.trajectories.
SplinedTrajectory
(dt=1, t0=0)¶ - A splined trajectory with knot spacing dt and time offset t0. The time offset t0 is the first valid time of the spline.
-
dt
¶ Spline knot spacing
-
t0
¶ Spline time offset (always same as
Trajectory.min_time
)
-
__len__
() → int¶ Number of spline knots and control points
-
__getitem__
(k : int) → ndarray¶ Return control point k
-
__setitem__
(k : int, cp : ndarray)¶ Set control point k
-
append_knot
(cp : ndarray)¶ Append a new control point (and knot)
-
extend_to
(t : float, cp : ndarray)¶ Extend the spline to be valid at least up to t by appending control points cp
-
Splined trajectory classes¶
-
class
kontiki.trajectories.
UniformSE3SplineTrajectory
¶ A spline with control points in SE(3)
Control points are 4x4 matrices T = [R, p; 0, 1].
-
class
kontiki.trajectories.
UniformR3SplineTrajectory
¶ A spline with control points in R3
Control points are vectors in R3.
-
class
kontiki.trajectories.
UniformSO3SplineTrajectory
¶ A spline with control points in SO(3)
Control points are unit quaternions q=(w, x, y, z).
Other trajectories¶
-
class
kontiki.trajectories.
SplitTrajectory
¶ Split interpolation trajectory
This trajectory is implemented using two splines: one in R3 and one in SO3.
-
SplitTrajectory
(r3_dt=1, so3_dt=1, r3_t0=0, so3_t0=0)¶ Construct new split trajectory from specified knot spacings and time offsets.
-
SplitTrajectory
(r3_trajectory, so3_trajectory) Construct split trajectory by wrapping two previously created
UniformR3SplineTrajectory
andUniformSO3SplineTrajectory
instances.
-
R3_spline
¶ The
UniformR3SplineTrajectory
instance
-
SO3_spline
¶ The
UniformSO3SplineTrajectory
instance
-
References
[Qin2000] | Qin, K. General matrix representations for b-splines The Visual Computer, 16(3–4) |