EllipticalRegionConstraint

class wpimath.trajectory.constraint.EllipticalRegionConstraint(*args, **kwargs)

Bases: TrajectoryConstraint

Enforces a particular constraint only within an elliptical region.

Overloaded function.

  1. __init__(self: wpimath._controls._controls.constraint.EllipticalRegionConstraint, center: wpimath.geometry._geometry.Translation2d, xWidth: wpimath.units.meters, yWidth: wpimath.units.meters, rotation: wpimath.geometry._geometry.Rotation2d, constraint: wpimath._controls._controls.constraint.TrajectoryConstraint) -> None

Constructs a new EllipticalRegionConstraint.

Deprecated:

Use constructor taking Ellipse2d instead.

Parameters:
  • center – The center of the ellipse in which to enforce the constraint.

  • xWidth – The width of the ellipse in which to enforce the constraint.

  • yWidth – The height of the ellipse in which to enforce the constraint.

  • rotation – The rotation to apply to all radii around the origin.

  • constraint – The constraint to enforce when the robot is within the region.

  1. __init__(self: wpimath._controls._controls.constraint.EllipticalRegionConstraint, ellipse: wpimath.geometry._geometry.Ellipse2d, constraint: wpimath._controls._controls.constraint.TrajectoryConstraint) -> None

Constructs a new EllipticalRegionConstraint.

Parameters:
  • ellipse – The ellipse in which to enforce the constraint.

  • constraint – The constraint to enforce when the robot is within the region.

static fromFeet(center: wpimath.geometry._geometry.Translation2d, xWidth: wpimath.units.feet, yWidth: wpimath.units.feet, rotation: wpimath.geometry._geometry.Rotation2d, constraint: wpimath._controls._controls.constraint.TrajectoryConstraint) wpimath._controls._controls.constraint.EllipticalRegionConstraint
maxVelocity(pose: wpimath.geometry._geometry.Pose2d, curvature: wpimath.units.radians_per_meter, velocity: wpimath.units.meters_per_second) wpimath.units.meters_per_second
minMaxAcceleration(pose: wpimath.geometry._geometry.Pose2d, curvature: wpimath.units.radians_per_meter, speed: wpimath.units.meters_per_second) wpimath._controls._controls.constraint.TrajectoryConstraint.MinMax