WPILibC++  2020.3.2
Transform2d.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 "Translation2d.h"
11 
12 namespace frc {
13 
14 class Pose2d;
15 
19 class Transform2d {
20  public:
27  Transform2d(Pose2d initial, Pose2d final);
28 
35  Transform2d(Translation2d translation, Rotation2d rotation);
36 
40  constexpr Transform2d() = default;
41 
47  const Translation2d& Translation() const { return m_translation; }
48 
54  const Rotation2d& Rotation() const { return m_rotation; }
55 
62  Transform2d operator*(double scalar) const {
63  return Transform2d(m_translation * scalar, m_rotation * scalar);
64  }
65 
72  bool operator==(const Transform2d& other) const;
73 
80  bool operator!=(const Transform2d& other) const;
81 
82  private:
83  Translation2d m_translation;
84  Rotation2d m_rotation;
85 };
86 } // namespace frc
frc::Transform2d::operator*
Transform2d operator*(double scalar) const
Scales the transform by the scalar.
Definition: Transform2d.h:62
frc::Transform2d::operator!=
bool operator!=(const Transform2d &other) const
Checks inequality between this Transform2d and another object.
frc::Transform2d::Transform2d
constexpr Transform2d()=default
Constructs the identity transform – maps an initial pose to itself.
frc::Transform2d::Rotation
const Rotation2d & Rotation() const
Returns the rotational component of the transformation.
Definition: Transform2d.h:54
frc::Rotation2d
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:22
frc::Transform2d
Represents a transformation for a Pose2d.
Definition: Transform2d.h:19
frc::Translation2d
Represents a translation in 2d space.
Definition: Translation2d.h:28
frc::Transform2d::Translation
const Translation2d & Translation() const
Returns the translation component of the transformation.
Definition: Transform2d.h:47
frc::Pose2d
Represents a 2d pose containing translational and rotational elements.
Definition: Pose2d.h:23
frc::Transform2d::operator==
bool operator==(const Transform2d &other) const
Checks equality between this Transform2d and another object.
frc
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16