mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpimath] Add vector projection and geometry vector conversions (#6343)
This commit is contained in:
@@ -11,6 +11,9 @@
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Translation2d::Translation2d(const Eigen::Vector2d& vector)
|
||||
: m_x{units::meter_t{vector.x()}}, m_y{units::meter_t{vector.y()}} {}
|
||||
|
||||
units::meter_t Translation2d::Distance(const Translation2d& other) const {
|
||||
return units::math::hypot(other.m_x - m_x, other.m_y - m_y);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user