Package-level declarations

Types

Link copied to clipboard
fun interface AccelConstraint
Link copied to clipboard
class AngularVelConstraint(val maxAngVel: Double) : VelConstraint
Link copied to clipboard
@Serializable
@SerialName(value = "CancelableProfile")
class CancelableProfile(val baseProfile: DisplacementProfile, val disps: List<Double>, val minAccels: List<Double>) : Profile

Displacement profile that can be canceled at any time to yield a new displacement profile that achieves the final velocity as soon as possible and then promptly ends.

Link copied to clipboard
class CompositeAccelConstraint(val constraints: List<AccelConstraint>, val offsets: List<Double>) : AccelConstraint
Link copied to clipboard
class CompositeVelConstraint(val constraints: List<VelConstraint>, val offsets: List<Double>) : VelConstraint
Link copied to clipboard
@Serializable
@SerialName(value = "DisplacementProfile")
data class DisplacementProfile(val disps: List<Double>, val vels: List<Double>, val accels: List<Double>) : Profile

Acceleration-limited motion profile parameterized by displacement.

Link copied to clipboard
Link copied to clipboard
interface Profile
Link copied to clipboard
class ProfileAccelConstraint(val minAccel: Double, val maxAccel: Double) : AccelConstraint
Link copied to clipboard
data class ProfileParams(val dispResolution: Double, val angResolution: Double, val angSamplingEps: Double)
Link copied to clipboard
@Serializable
@SerialName(value = "TimeProfile")
data class TimeProfile @JvmOverloads constructor(val dispProfile: DisplacementProfile, val times: List<Double> = timeScan(dispProfile)) : Profile

Acceleration-limited motion profile parameterized by time.

Link copied to clipboard
Link copied to clipboard
fun interface VelConstraint

Functions

Link copied to clipboard
fun backwardProfile(disps: List<Double>, maxVels: List<Double>, endVel: Double, minAccels: List<Double>): DisplacementProfile

Computes an approximately time-optimal backward profile from the center-sampled constraints. No restriction is imposed on the maximum acceleration.

fun backwardProfile(params: ProfileParams, path: PosePath, velConstraint: VelConstraint, endVel: Double, accelConstraint: AccelConstraint): DisplacementProfile

fun backwardProfile(length: Double, maxVel: (Double) -> Double, endVel: Double, minAccel: (Double) -> Double, resolution: Double): DisplacementProfile

Computes an approximately time-optimal backward profile by sampling the constraints according to the resolution resolution. No restriction is imposed on the minimum acceleration.

Link copied to clipboard
fun constantProfile(length: Double, beginEndVel: Double, maxVel: Double, minAccel: Double, maxAccel: Double): CancelableProfile

Computes an exact, time-optimal profile.

Link copied to clipboard
fun forwardProfile(disps: List<Double>, beginVel: Double, maxVels: List<Double>, maxAccels: List<Double>): DisplacementProfile

Computes an approximately time-optimal forward profile from the center-sampled constraints. No restriction is imposed on the minimum acceleration.

fun forwardProfile(params: ProfileParams, path: PosePath, beginVel: Double, velConstraint: VelConstraint, accelConstraint: AccelConstraint): DisplacementProfile

fun forwardProfile(length: Double, beginVel: Double, maxVel: (Double) -> Double, maxAccel: (Double) -> Double, resolution: Double): DisplacementProfile

Computes an approximately time-optimal forward profile by sampling the constraints according to the resolution resolution. No restriction is imposed on the minimum acceleration.

Link copied to clipboard

Merges p1 and p2 into another profile with the minimum velocity of the two at every point.

Link copied to clipboard
Link copied to clipboard
fun profile(params: ProfileParams, path: PosePath, beginEndVel: Double, velConstraint: VelConstraint, accelConstraint: AccelConstraint): CancelableProfile

fun profile(disps: List<Double>, beginEndVel: Double, maxVels: List<Double>, minAccels: List<Double>, maxAccels: List<Double>): CancelableProfile

Computes an approximately time-optimal profile from sampled constraints.

fun profile(length: Double, beginEndVel: Double, maxVel: (Double) -> Double, minAccel: (Double) -> Double, maxAccel: (Double) -> Double, resolution: Double): CancelableProfile

Computes an approximately time-optimal profile by sampling the constraints according to the resolution resolution.

Link copied to clipboard
fun samplePathByRotation(path: PosePath, angResolution: Double, eps: Double): List<Double>