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,32 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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::DifferentialDriveWheelSpeeds Drivetrain::GetSpeeds() const {
|
||||
return {units::meters_per_second_t(m_leftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rightEncoder.GetRate())};
|
||||
}
|
||||
|
||||
void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
|
||||
const auto leftOutput = m_leftPIDController.Calculate(
|
||||
m_leftEncoder.GetRate(), speeds.left.to<double>());
|
||||
const auto rightOutput = m_rightPIDController.Calculate(
|
||||
m_rightEncoder.GetRate(), speeds.right.to<double>());
|
||||
|
||||
m_leftGroup.Set(leftOutput);
|
||||
m_rightGroup.Set(rightOutput);
|
||||
}
|
||||
|
||||
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot) {
|
||||
SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot}));
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(GetAngle(), GetSpeeds());
|
||||
}
|
||||
@@ -0,0 +1,43 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 {
|
||||
TeleopPeriodic();
|
||||
m_drive.UpdateOdometry();
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// 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 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_drive.Drive(xSpeed, rot);
|
||||
}
|
||||
|
||||
private:
|
||||
frc::XboxController m_controller{0};
|
||||
Drivetrain m_drive;
|
||||
};
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() { return frc::StartRobot<Robot>(); }
|
||||
#endif
|
||||
@@ -0,0 +1,79 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 <units/units.h>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Spark.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <wpi/math>
|
||||
|
||||
/**
|
||||
* Represents a differential drive style drivetrain.
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
// Set the distance per pulse for the drive encoders. We can simply use the
|
||||
// distance traveled for one rotation of the wheel divided by the encoder
|
||||
// resolution.
|
||||
m_leftEncoder.SetDistancePerPulse(2 * wpi::math::pi * kWheelRadius /
|
||||
kEncoderResolution);
|
||||
m_rightEncoder.SetDistancePerPulse(2 * wpi::math::pi * kWheelRadius /
|
||||
kEncoderResolution);
|
||||
}
|
||||
|
||||
/**
|
||||
* 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()));
|
||||
}
|
||||
|
||||
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
|
||||
|
||||
frc::DifferentialDriveWheelSpeeds GetSpeeds() const;
|
||||
void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot);
|
||||
void UpdateOdometry();
|
||||
|
||||
private:
|
||||
static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
|
||||
static constexpr double kWheelRadius = 0.0508; // meters
|
||||
static constexpr int kEncoderResolution = 4096;
|
||||
|
||||
frc::Spark m_leftMaster{1};
|
||||
frc::Spark m_leftFollower{2};
|
||||
frc::Spark m_rightMaster{3};
|
||||
frc::Spark m_rightFollower{4};
|
||||
|
||||
frc::SpeedControllerGroup m_leftGroup{m_leftMaster, m_leftFollower};
|
||||
frc::SpeedControllerGroup m_rightGroup{m_rightMaster, m_rightFollower};
|
||||
|
||||
frc::Encoder m_leftEncoder{0, 1};
|
||||
frc::Encoder m_rightEncoder{0, 1};
|
||||
|
||||
frc2::PIDController m_leftPIDController{1.0, 0.0, 0.0};
|
||||
frc2::PIDController m_rightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{m_kinematics};
|
||||
};
|
||||
Reference in New Issue
Block a user