mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Add kinematics suite (#1787)
Co-authored-by: Tyler Veness <calcmogul@gmail.com> Co-authored-by: Matt <matthew.morley.ca@gmail.com>
This commit is contained in:
committed by
Peter Johnson
parent
561cbbd144
commit
f405582f86
@@ -0,0 +1,61 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/kinematics/SwerveDriveOdometry.h>
|
||||
#include <wpi/math>
|
||||
|
||||
#include "SwerveModule.h"
|
||||
|
||||
/**
|
||||
* Represents a swerve drive style drivetrain.
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
|
||||
/**
|
||||
* Get the robot angle as a Rotation2d.
|
||||
*/
|
||||
frc::Rotation2d GetAngle() const {
|
||||
// Negating the angle because WPILib Gyros are CW positive.
|
||||
return frc::Rotation2d(units::degree_t(-m_gyro.GetAngle()));
|
||||
}
|
||||
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
|
||||
bool fieldRelative);
|
||||
void UpdateOdometry();
|
||||
|
||||
static constexpr units::meters_per_second_t kMaxSpeed =
|
||||
3.0_mps; // 3 meters per second
|
||||
static constexpr units::radians_per_second_t kMaxAngularSpeed{
|
||||
wpi::math::pi}; // 1/2 rotation per second
|
||||
|
||||
private:
|
||||
frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
|
||||
frc::Translation2d m_frontRightLocation{+0.381_m, -0.381_m};
|
||||
frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m};
|
||||
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
|
||||
|
||||
SwerveModule m_frontLeft{1, 2};
|
||||
SwerveModule m_frontRight{2, 3};
|
||||
SwerveModule m_backLeft{5, 6};
|
||||
SwerveModule m_backRight{7, 8};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
|
||||
frc::SwerveDriveKinematics<4> m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
m_backRightLocation};
|
||||
|
||||
frc::SwerveDriveOdometry<4> m_odometry{m_kinematics};
|
||||
};
|
||||
Reference in New Issue
Block a user