CoordinateSystem
- class wpimath.CoordinateSystem(positiveX: wpimath._wpimath.CoordinateAxis, positiveY: wpimath._wpimath.CoordinateAxis, positiveZ: wpimath._wpimath.CoordinateAxis)
Bases:
pybind11_objectA helper class that converts Pose3d objects between different standard coordinate frames.
Constructs a coordinate system with the given cardinal directions for each axis.
- Parameters:
positiveX – The cardinal direction of the positive x-axis.
positiveY – The cardinal direction of the positive y-axis.
positiveZ – The cardinal direction of the positive z-axis. @throws std::domain_error if the coordinate system isn’t special orthogonal
- static EDN() wpimath._wpimath.CoordinateSystem
Returns an instance of the East-Down-North (EDN) coordinate system.
The +X axis is east, the +Y axis is down, and the +Z axis is north.
- static NED() wpimath._wpimath.CoordinateSystem
Returns an instance of the NED coordinate system.
The +X axis is north, the +Y axis is east, and the +Z axis is down.
- static NWU() wpimath._wpimath.CoordinateSystem
Returns an instance of the North-West-Up (NWU) coordinate system.
The +X axis is north, the +Y axis is west, and the +Z axis is up.
- static convert(*args, **kwargs)
Overloaded function.
convert(translation: wpimath._wpimath.Translation3d, from_: wpimath._wpimath.CoordinateSystem, to: wpimath._wpimath.CoordinateSystem) -> wpimath._wpimath.Translation3d
Converts the given translation from one coordinate system to another.
- Parameters:
translation – The translation to convert.
from – The coordinate system the translation starts in.
to – The coordinate system to which to convert.
- Returns:
The given translation in the desired coordinate system.
convert(rotation: wpimath._wpimath.Rotation3d, from_: wpimath._wpimath.CoordinateSystem, to: wpimath._wpimath.CoordinateSystem) -> wpimath._wpimath.Rotation3d
Converts the given rotation from one coordinate system to another.
- Parameters:
rotation – The rotation to convert.
from – The coordinate system the rotation starts in.
to – The coordinate system to which to convert.
- Returns:
The given rotation in the desired coordinate system.
convert(pose: wpimath._wpimath.Pose3d, from_: wpimath._wpimath.CoordinateSystem, to: wpimath._wpimath.CoordinateSystem) -> wpimath._wpimath.Pose3d
Converts the given pose from one coordinate system to another.
- Parameters:
pose – The pose to convert.
from – The coordinate system the pose starts in.
to – The coordinate system to which to convert.
- Returns:
The given pose in the desired coordinate system.
convert(transform: wpimath._wpimath.Transform3d, from_: wpimath._wpimath.CoordinateSystem, to: wpimath._wpimath.CoordinateSystem) -> wpimath._wpimath.Transform3d
Converts the given transform from one coordinate system to another.
- Parameters:
transform – The transform to convert.
from – The coordinate system the transform starts in.
to – The coordinate system to which to convert.
- Returns:
The given transform in the desired coordinate system.