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,46 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "Drivetrain.h"
|
||||
|
||||
frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
|
||||
return {units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_backLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_backRightEncoder.GetRate())};
|
||||
}
|
||||
|
||||
void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
|
||||
const auto frontLeftOutput = m_frontLeftPIDController.Calculate(
|
||||
m_frontLeftEncoder.GetRate(), wheelSpeeds.frontLeft.to<double>());
|
||||
const auto frontRightOutput = m_frontRightPIDController.Calculate(
|
||||
m_frontRightEncoder.GetRate(), wheelSpeeds.frontRight.to<double>());
|
||||
const auto backLeftOutput = m_backLeftPIDController.Calculate(
|
||||
m_backLeftEncoder.GetRate(), wheelSpeeds.rearLeft.to<double>());
|
||||
const auto backRightOutput = m_backRightPIDController.Calculate(
|
||||
m_backRightEncoder.GetRate(), wheelSpeeds.rearRight.to<double>());
|
||||
|
||||
m_frontLeftMotor.Set(frontLeftOutput);
|
||||
m_frontRightMotor.Set(frontRightOutput);
|
||||
m_backLeftMotor.Set(backLeftOutput);
|
||||
m_backRightMotor.Set(backRightOutput);
|
||||
}
|
||||
|
||||
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::meters_per_second_t ySpeed,
|
||||
units::radians_per_second_t rot, bool fieldRelative) {
|
||||
auto wheelSpeeds = m_kinematics.ToWheelSpeeds(
|
||||
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, GetAngle())
|
||||
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
|
||||
wheelSpeeds.Normalize(kMaxSpeed);
|
||||
SetSpeeds(wheelSpeeds);
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(GetAngle(), GetCurrentState());
|
||||
}
|
||||
@@ -0,0 +1,51 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
|
||||
#include "Drivetrain.h"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void AutonomousPeriodic() override {
|
||||
DriveWithJoystick(false);
|
||||
m_mecanum.UpdateOdometry();
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override { DriveWithJoystick(true); }
|
||||
|
||||
private:
|
||||
frc::XboxController m_controller{0};
|
||||
Drivetrain m_mecanum;
|
||||
|
||||
void DriveWithJoystick(bool fieldRelative) {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// negative values when we push forward.
|
||||
const auto xSpeed =
|
||||
-m_controller.GetY(frc::GenericHID::kLeftHand) * Drivetrain::kMaxSpeed;
|
||||
|
||||
// Get the y speed or sideways/strafe speed. We are inverting this because
|
||||
// we want a positive value when we pull to the left. Xbox controllers
|
||||
// return positive values when you pull to the right by default.
|
||||
const auto ySpeed =
|
||||
-m_controller.GetX(frc::GenericHID::kLeftHand) * Drivetrain::kMaxSpeed;
|
||||
|
||||
// Get the rate of angular rotation. We are inverting this because we want a
|
||||
// positive value when we pull to the left (remember, CCW is positive in
|
||||
// mathematics). Xbox controllers return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_controller.GetX(frc::GenericHID::kRightHand) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
|
||||
m_mecanum.Drive(xSpeed, ySpeed, rot, fieldRelative);
|
||||
}
|
||||
};
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() { return frc::StartRobot<Robot>(); }
|
||||
#endif
|
||||
@@ -0,0 +1,75 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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/Encoder.h>
|
||||
#include <frc/Spark.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/MecanumDriveKinematics.h>
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <wpi/math>
|
||||
|
||||
/**
|
||||
* Represents a mecanum 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()));
|
||||
}
|
||||
|
||||
frc::MecanumDriveWheelSpeeds GetCurrentState() const;
|
||||
void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
|
||||
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::Spark m_frontLeftMotor{1};
|
||||
frc::Spark m_frontRightMotor{2};
|
||||
frc::Spark m_backLeftMotor{3};
|
||||
frc::Spark m_backRightMotor{4};
|
||||
|
||||
frc::Encoder m_frontLeftEncoder{0, 1};
|
||||
frc::Encoder m_frontRightEncoder{0, 1};
|
||||
frc::Encoder m_backLeftEncoder{0, 1};
|
||||
frc::Encoder m_backRightEncoder{0, 1};
|
||||
|
||||
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};
|
||||
|
||||
frc2::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
|
||||
frc2::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
|
||||
frc2::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
|
||||
frc2::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
|
||||
frc::MecanumDriveKinematics m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
m_backRightLocation};
|
||||
|
||||
frc::MecanumDriveOdometry m_odometry{m_kinematics};
|
||||
};
|
||||
Reference in New Issue
Block a user