WPILibC++  2020.3.2
Translation2d.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) 2019 FIRST. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in the root directory of */
5 /* the project. */
6 /*----------------------------------------------------------------------------*/
7 
8 #pragma once
9 
10 #include <units/units.h>
11 
12 #include "Rotation2d.h"
13 
14 namespace wpi {
15 class json;
16 } // namespace wpi
17 
18 namespace frc {
19 
29  public:
33  constexpr Translation2d() = default;
34 
42  Translation2d(units::meter_t x, units::meter_t y);
43 
54  units::meter_t Distance(const Translation2d& other) const;
55 
61  units::meter_t X() const { return m_x; }
62 
68  units::meter_t Y() const { return m_y; }
69 
75  units::meter_t Norm() const;
76 
93  Translation2d RotateBy(const Rotation2d& other) const;
94 
106  Translation2d operator+(const Translation2d& other) const;
107 
118  Translation2d& operator+=(const Translation2d& other);
119 
131  Translation2d operator-(const Translation2d& other) const;
132 
143  Translation2d& operator-=(const Translation2d& other);
144 
152  Translation2d operator-() const;
153 
163  Translation2d operator*(double scalar) const;
164 
174  Translation2d& operator*=(double scalar);
175 
185  Translation2d operator/(double scalar) const;
186 
193  bool operator==(const Translation2d& other) const;
194 
201  bool operator!=(const Translation2d& other) const;
202 
203  /*
204  * Divides the current translation by a scalar.
205  *
206  * This is similar to the / operator, except that current object is mutated.
207  *
208  * @param scalar The scalar to divide by.
209  *
210  * @return The reference to the new mutated object.
211  */
212  Translation2d& operator/=(double scalar);
213 
214  private:
215  units::meter_t m_x = 0_m;
216  units::meter_t m_y = 0_m;
217 };
218 
219 void to_json(wpi::json& json, const Translation2d& state);
220 
221 void from_json(const wpi::json& json, Translation2d& state);
222 
223 } // namespace frc
wpi::json
a class to store JSON values
Definition: json.h:2655
frc::Translation2d::Translation2d
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
frc::Translation2d::Norm
units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
frc::Translation2d::X
units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:61
frc::Rotation2d
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:22
frc::Translation2d::operator==
bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
frc::Translation2d
Represents a translation in 2d space.
Definition: Translation2d.h:28
wpi
WPILib C++ utilities (wpiutil) namespace.
Definition: EventLoopRunner.h:17
frc::Translation2d::operator/
Translation2d operator/(double scalar) const
Divides the translation by a scalar and returns the new translation.
frc::Translation2d::Distance
units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2d space.
frc::Translation2d::operator!=
bool operator!=(const Translation2d &other) const
Checks inequality between this Translation2d and another object.
frc::Translation2d::operator-
Translation2d operator-() const
Returns the inverse of the current translation.
frc::Translation2d::operator*
Translation2d operator*(double scalar) const
Multiplies the translation by a scalar and returns the new translation.
frc::Translation2d::operator+
Translation2d operator+(const Translation2d &other) const
Adds two translations in 2d space and returns the sum.
frc
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16
frc::Translation2d::operator-=
Translation2d & operator-=(const Translation2d &other)
Subtracts the new translation from the current translation.
frc::Translation2d::Y
units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:68
frc::Translation2d::operator+=
Translation2d & operator+=(const Translation2d &other)
Adds the new translation to the current translation.
frc::Translation2d::operator*=
Translation2d & operator*=(double scalar)
Multiplies the current translation by a scalar.
frc::Translation2d::RotateBy
Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2d space.