mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Add overloads for Transform2d and Transform3d (#5757)
Adds overloads for Transform2d() constructor to accept x, y, and heading and for Transform3d() to accept x, y, z and rotation as a shorthand for the normal constructors.
This commit is contained in:
@@ -21,6 +21,10 @@ Transform3d::Transform3d(Pose3d initial, Pose3d final) {
|
||||
Transform3d::Transform3d(Translation3d translation, Rotation3d rotation)
|
||||
: m_translation(std::move(translation)), m_rotation(std::move(rotation)) {}
|
||||
|
||||
Transform3d::Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
|
||||
Rotation3d rotation)
|
||||
: m_translation(x, y, z), m_rotation(std::move(rotation)) {}
|
||||
|
||||
Transform3d Transform3d::Inverse() const {
|
||||
// We are rotating the difference between the translations
|
||||
// using a clockwise rotation matrix. This transforms the global
|
||||
|
||||
Reference in New Issue
Block a user