pymoveit_mtc.core.PathLength¶
- class PathLength(*args, **kwargs)¶
Bases:
TrajectoryCostTerm
Computes joint-based path length along trajectory
Overloaded function.
__init__(self: pymoveit_mtc.core.PathLength) -> None
__init__(self: pymoveit_mtc.core.PathLength, arg0: collections.abc.Sequence[str]) -> None
__init__(self: pymoveit_mtc.core.PathLength, arg0: collections.abc.Mapping[str, typing.SupportsFloat]) -> None
Methods
- class Mode(self: pymoveit_mtc.core.TrajectoryCostTerm.Mode, value: SupportsInt)¶
Bases:
pybind11_object
Specify which states are considered for collision checking
Members:
AUTO : TRAJECTORY (if available) or START_INTERFACE
START_INTERFACE : Only consider start state
END_INTERFACE : Only consider end state
TRAJECTORY : Consider whole trajectory
- property name¶