[wpimath] Add vector projection and geometry vector conversions (#6343)

This commit is contained in:
Asa Paparo
2024-02-10 13:43:58 -05:00
committed by GitHub
parent 3207795d0d
commit 62cba9a4d3
21 changed files with 234 additions and 24 deletions

View File

@@ -13,11 +13,11 @@
namespace frc {
constexpr Pose2d::Pose2d(Translation2d translation, Rotation2d rotation)
: m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
: m_translation{std::move(translation)}, m_rotation{std::move(rotation)} {}
constexpr Pose2d::Pose2d(units::meter_t x, units::meter_t y,
Rotation2d rotation)
: m_translation(x, y), m_rotation(std::move(rotation)) {}
: m_translation{x, y}, m_rotation{std::move(rotation)} {}
constexpr Pose2d Pose2d::operator+(const Transform2d& other) const {
return TransformBy(other);

View File

@@ -12,9 +12,9 @@
namespace frc {
constexpr Rotation2d::Rotation2d(units::angle_unit auto value)
: m_value(value),
m_cos(gcem::cos(value.template convert<units::radian>().value())),
m_sin(gcem::sin(value.template convert<units::radian>().value())) {}
: m_value{value},
m_cos{gcem::cos(value.template convert<units::radian>().value())},
m_sin{gcem::sin(value.template convert<units::radian>().value())} {}
constexpr Rotation2d::Rotation2d(double x, double y) {
double magnitude = gcem::hypot(x, y);
@@ -33,7 +33,7 @@ constexpr Rotation2d Rotation2d::operator-() const {
}
constexpr Rotation2d Rotation2d::operator*(double scalar) const {
return Rotation2d(m_value * scalar);
return Rotation2d{m_value * scalar};
}
constexpr Rotation2d Rotation2d::operator+(const Rotation2d& other) const {

View File

@@ -14,11 +14,11 @@ namespace frc {
constexpr Transform2d::Transform2d(Translation2d translation,
Rotation2d rotation)
: m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
: m_translation{std::move(translation)}, m_rotation{std::move(rotation)} {}
constexpr Transform2d::Transform2d(units::meter_t x, units::meter_t y,
Rotation2d rotation)
: m_translation(x, y), m_rotation(std::move(rotation)) {}
: m_translation{x, y}, m_rotation{std::move(rotation)} {}
constexpr Transform2d Transform2d::Inverse() const {
// We are rotating the difference between the translations

View File

@@ -7,6 +7,7 @@
#include <initializer_list>
#include <span>
#include <Eigen/Core>
#include <wpi/SymbolExports.h>
#include <wpi/json_fwd.h>
@@ -48,6 +49,14 @@ class WPILIB_DLLEXPORT Translation2d {
*/
constexpr Translation2d(units::meter_t distance, const Rotation2d& angle);
/**
* Constructs a Translation2d from the provided translation vector's X and Y
* components. The values are assumed to be in meters.
*
* @param vector The translation vector to represent.
*/
explicit Translation2d(const Eigen::Vector2d& vector);
/**
* Calculates the distance between two translations in 2D space.
*
@@ -73,6 +82,13 @@ class WPILIB_DLLEXPORT Translation2d {
*/
constexpr units::meter_t Y() const { return m_y; }
/**
* Returns a vector representation of this translation.
*
* @return A Vector representation of this translation.
*/
constexpr Eigen::Vector2d ToVector() const;
/**
* Returns the norm, or distance from the origin to the translation.
*

View File

@@ -10,11 +10,15 @@
namespace frc {
constexpr Translation2d::Translation2d(units::meter_t x, units::meter_t y)
: m_x(x), m_y(y) {}
: m_x{x}, m_y{y} {}
constexpr Translation2d::Translation2d(units::meter_t distance,
const Rotation2d& angle)
: m_x(distance * angle.Cos()), m_y(distance * angle.Sin()) {}
: m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
constexpr Eigen::Vector2d Translation2d::ToVector() const {
return Eigen::Vector2d{{m_x.value(), m_y.value()}};
}
constexpr Rotation2d Translation2d::Angle() const {
return Rotation2d{m_x.value(), m_y.value()};

View File

@@ -4,6 +4,7 @@
#pragma once
#include <Eigen/Core>
#include <wpi/SymbolExports.h>
#include <wpi/json_fwd.h>
@@ -47,6 +48,14 @@ class WPILIB_DLLEXPORT Translation3d {
*/
Translation3d(units::meter_t distance, const Rotation3d& angle);
/**
* Constructs a Translation3d from the provided translation vector's X, Y, and
* Z components. The values are assumed to be in meters.
*
* @param vector The translation vector to represent.
*/
explicit Translation3d(const Eigen::Vector3d& vector);
/**
* Calculates the distance between two translations in 3D space.
*
@@ -80,6 +89,13 @@ class WPILIB_DLLEXPORT Translation3d {
*/
constexpr units::meter_t Z() const { return m_z; }
/**
* Returns a vector representation of this translation.
*
* @return A Vector representation of this translation.
*/
constexpr Eigen::Vector3d ToVector() const;
/**
* Returns the norm, or distance from the origin to the translation.
*

View File

@@ -13,12 +13,16 @@ namespace frc {
constexpr Translation3d::Translation3d(units::meter_t x, units::meter_t y,
units::meter_t z)
: m_x(x), m_y(y), m_z(z) {}
: m_x{x}, m_y{y}, m_z{z} {}
constexpr Translation2d Translation3d::ToTranslation2d() const {
return Translation2d{m_x, m_y};
}
constexpr Eigen::Vector3d Translation3d::ToVector() const {
return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
}
constexpr Translation3d Translation3d::operator+(
const Translation3d& other) const {
return {X() + other.X(), Y() + other.Y(), Z() + other.Z()};