001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.math.geometry; 006 007import static edu.wpi.first.units.Units.Meters; 008 009import edu.wpi.first.math.MathUtil; 010import edu.wpi.first.math.geometry.proto.Rectangle2dProto; 011import edu.wpi.first.math.geometry.struct.Rectangle2dStruct; 012import edu.wpi.first.units.measure.Distance; 013import edu.wpi.first.util.protobuf.ProtobufSerializable; 014import edu.wpi.first.util.struct.StructSerializable; 015import java.util.Objects; 016 017/** 018 * Represents a 2d rectangular space containing translational, rotational, and scaling components. 019 */ 020public class Rectangle2d implements ProtobufSerializable, StructSerializable { 021 private final Pose2d m_center; 022 private final double m_xWidth; 023 private final double m_yWidth; 024 025 /** 026 * Constructs a rectangle at the specified position with the specified width and height. 027 * 028 * @param center The position (translation and rotation) of the rectangle. 029 * @param xWidth The x size component of the rectangle, in unrotated coordinate frame. 030 * @param yWidth The y size component of the rectangle, in unrotated coordinate frame. 031 */ 032 public Rectangle2d(Pose2d center, double xWidth, double yWidth) { 033 if (xWidth < 0 || yWidth < 0) { 034 throw new IllegalArgumentException("Rectangle2d dimensions cannot be less than 0!"); 035 } 036 037 m_center = center; 038 m_xWidth = xWidth; 039 m_yWidth = yWidth; 040 } 041 042 /** 043 * Constructs a rectangle at the specified position with the specified width and height. The X and 044 * Y widths will be converted to and tracked as meters. 045 * 046 * @param center The position (translation and rotation) of the rectangle. 047 * @param xWidth The x size component of the rectangle, in unrotated coordinate frame. 048 * @param yWidth The y size component of the rectangle, in unrotated coordinate frame. 049 */ 050 public Rectangle2d(Pose2d center, Distance xWidth, Distance yWidth) { 051 this(center, xWidth.in(Meters), yWidth.in(Meters)); 052 } 053 054 /** 055 * Creates an unrotated rectangle from the given corners. The corners should be diagonally 056 * opposite of each other. 057 * 058 * @param cornerA The first corner of the rectangle. 059 * @param cornerB The second corner of the rectangle. 060 */ 061 public Rectangle2d(Translation2d cornerA, Translation2d cornerB) { 062 this( 063 new Pose2d(cornerA.plus(cornerB).div(2.0), Rotation2d.kZero), 064 Math.abs(cornerA.getX() - cornerB.getX()), 065 Math.abs(cornerA.getY() - cornerB.getY())); 066 } 067 068 /** 069 * Returns the center of the rectangle. 070 * 071 * @return The center of the rectangle. 072 */ 073 public Pose2d getCenter() { 074 return m_center; 075 } 076 077 /** 078 * Returns the rotational component of the rectangle. 079 * 080 * @return The rotational component of the rectangle. 081 */ 082 public Rotation2d getRotation() { 083 return m_center.getRotation(); 084 } 085 086 /** 087 * Returns the x size component of the rectangle. 088 * 089 * @return The x size component of the rectangle. 090 */ 091 public double getXWidth() { 092 return m_xWidth; 093 } 094 095 /** 096 * Returns the y size component of the rectangle. 097 * 098 * @return The y size component of the rectangle. 099 */ 100 public double getYWidth() { 101 return m_yWidth; 102 } 103 104 /** 105 * Returns the X size component of the rectangle in a measure. 106 * 107 * @return The x size component of the rectangle in a measure. 108 */ 109 public Distance getMeasureXWidth() { 110 return Meters.of(m_xWidth); 111 } 112 113 /** 114 * Returns the Y size component of the rectangle in a measure. 115 * 116 * @return The y size component of the rectangle in a measure. 117 */ 118 public Distance getMeasureYWidth() { 119 return Meters.of(m_yWidth); 120 } 121 122 /** 123 * Transforms the center of the rectangle and returns the new rectangle. 124 * 125 * @param other The transform to transform by. 126 * @return The transformed rectangle 127 */ 128 public Rectangle2d transformBy(Transform2d other) { 129 return new Rectangle2d(m_center.transformBy(other), m_xWidth, m_yWidth); 130 } 131 132 /** 133 * Rotates the center of the rectangle and returns the new rectangle. 134 * 135 * @param other The rotation to transform by. 136 * @return The rotated rectangle. 137 */ 138 public Rectangle2d rotateBy(Rotation2d other) { 139 return new Rectangle2d(m_center.rotateBy(other), m_xWidth, m_yWidth); 140 } 141 142 /** 143 * Checks if a point is intersected by the rectangle's perimeter. 144 * 145 * @param point The point to check. 146 * @return True, if the rectangle's perimeter intersects the point. 147 */ 148 public boolean intersects(Translation2d point) { 149 // Move the point into the rectangle's coordinate frame 150 point = point.minus(m_center.getTranslation()); 151 point = point.rotateBy(m_center.getRotation().unaryMinus()); 152 153 if (Math.abs(Math.abs(point.getX()) - m_xWidth / 2.0) <= 1E-9) { 154 // Point rests on left/right perimeter 155 return Math.abs(point.getY()) <= m_yWidth / 2.0; 156 } else if (Math.abs(Math.abs(point.getY()) - m_yWidth / 2.0) <= 1E-9) { 157 // Point rests on top/bottom perimeter 158 return Math.abs(point.getX()) <= m_xWidth / 2.0; 159 } 160 161 return false; 162 } 163 164 /** 165 * Checks if a point is contained within the rectangle. This is inclusive, if the point lies on 166 * the perimeter it will return true. 167 * 168 * @param point The point to check. 169 * @return True, if the rectangle contains the point or the perimeter intersects the point. 170 */ 171 public boolean contains(Translation2d point) { 172 // Rotate the point into the rectangle's coordinate frame 173 point = point.rotateAround(m_center.getTranslation(), m_center.getRotation().unaryMinus()); 174 175 // Check if within bounding box 176 return point.getX() >= (m_center.getX() - m_xWidth / 2.0) 177 && point.getX() <= (m_center.getX() + m_xWidth / 2.0) 178 && point.getY() >= (m_center.getY() - m_yWidth / 2.0) 179 && point.getY() <= (m_center.getY() + m_yWidth / 2.0); 180 } 181 182 /** 183 * Returns the distance between the perimeter of the rectangle and the point. 184 * 185 * @param point The point to check. 186 * @return The distance (0, if the point is contained by the rectangle) 187 */ 188 public double getDistance(Translation2d point) { 189 return nearest(point).getDistance(point); 190 } 191 192 /** 193 * Returns the distance between the perimeter of the rectangle and the point in a measure. 194 * 195 * @param point The point to check. 196 * @return The distance (0, if the point is contained by the rectangle) in a measure. 197 */ 198 public Distance getMeasureDistance(Translation2d point) { 199 return Meters.of(getDistance(point)); 200 } 201 202 /** 203 * Returns the nearest point that is contained within the rectangle. 204 * 205 * @param point The point that this will find the nearest point to. 206 * @return A new point that is nearest to {@code point} and contained in the rectangle. 207 */ 208 public Translation2d nearest(Translation2d point) { 209 // Check if already in rectangle 210 if (contains(point)) { 211 return point; 212 } 213 214 // Rotate the point by the inverse of the rectangle's rotation 215 point = point.rotateAround(m_center.getTranslation(), m_center.getRotation().unaryMinus()); 216 217 // Find nearest point 218 point = 219 new Translation2d( 220 MathUtil.clamp( 221 point.getX(), m_center.getX() - m_xWidth / 2.0, m_center.getX() + m_xWidth / 2.0), 222 MathUtil.clamp( 223 point.getY(), m_center.getY() - m_yWidth / 2.0, m_center.getY() + m_yWidth / 2.0)); 224 225 // Undo rotation 226 return point.rotateAround(m_center.getTranslation(), m_center.getRotation()); 227 } 228 229 @Override 230 public String toString() { 231 return String.format("Rectangle2d(center: %s, x: %.2f, y: %.2f)", m_center, m_xWidth, m_yWidth); 232 } 233 234 /** 235 * Checks equality between this Rectangle2d and another object. 236 * 237 * @param obj The other object. 238 * @return Whether the two objects are equal or not. 239 */ 240 @Override 241 public boolean equals(Object obj) { 242 if (obj instanceof Rectangle2d) { 243 return ((Rectangle2d) obj).getCenter().equals(m_center) 244 && ((Rectangle2d) obj).getXWidth() == m_xWidth 245 && ((Rectangle2d) obj).getYWidth() == m_yWidth; 246 } 247 return false; 248 } 249 250 @Override 251 public int hashCode() { 252 return Objects.hash(m_center, m_xWidth, m_yWidth); 253 } 254 255 /** Rectangle2d protobuf for serialization. */ 256 public static final Rectangle2dProto proto = new Rectangle2dProto(); 257 258 /** Rectangle2d struct for serialization. */ 259 public static final Rectangle2dStruct struct = new Rectangle2dStruct(); 260}