Expand description
This library generate smooth trajectories in cartesian space in a functional style.
§Overview
The idea is to specify a function that takes a start pose and a progress between 0 and 1 and spits out a pose.
This function is the PoseGenerator
. It is possible to directly define the function
or to combine a PositionGenerator
and an OrientationGenerator
.
Further, there are predefined PoseGenerators available. See pose_generators
.
You should make sure that your own PoseGenerators have a constant derivative, that means that all if you would sample 1000 equidistant points, the length between neighboring points should be the same. Otherwise, some parts of your trajectory will end up faster than other ones.
PoseGenerators can be multiplied to generate a new PoseGenerator. Multiplication means that the homogenous matrices of both pose generators will be multiplied together for a certain progress.
Further, it is possible to combine PoseGenerators with the append
method,
which will concatenate both PoseGenerators. Be aware that concatenating PoseGenerators can result in unsmooth
trajectories. For example, if you append a circle PoseGenerator to a linear PoseGenerator, there will be an infinite
jerk at the transition as the acceleration suddenly changes.
With the final PoseGenerator it is now possible to add a VelocityProfile to it, which turns
the PoseGenerator into a CartesianTrajectory
which can be queried
with the get_pose
method
with a start pose and a Duration.
The following images shows how this library can be used to create a complex trajectory
Re-exports§
pub use crate::pose_generators::generate_absolute_motion;
pub use crate::pose_generators::generate_circle_motion;
pub use crate::pose_generators::generate_relative_motion;
pub use crate::pose_generators::RelativeMotionFrame;
pub use s_curve;
Modules§
- pose_
generators - contains predefined PoseGenerators
Structs§
- Cartesian
Trajectory - Represents a trajectory in cartesian space. It contains a function which maps a start pose and time to the pose at that time and weather the trajectory is finished.
- Cartesian
Trajectory Output - Struct that describes the output of
get_pose
- Orientation
Generator - Struct that wraps a function that generates an orientation
- Pose
Generator - Struct that wraps a function that generates a pose
- Position
Generator - Struct that wraps a function that generates a position
- Velocity
Profile Mapping - Custom Velocity Profile
- Velocity
Profile Output - output of the get function of a
VelocityProfileMapping
Enums§
- Velocity
Profile - Select one of the predefined Velocity Profiles
Functions§
- generate_
cosine_ velocity_ profile - Generates a smooth cosine velocity profile which is indefinitely often continuously differentiable.
- generate_
linear_ velocity_ profile - Generates a simple Linear Velocity Profile. It linearly maps the duration to a progress.
- generate_
s_ curve_ profile - creates an S-Curve velocity profile which is subject to jerk, acceleration and velocity constraints