mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Add feed-forward and slew rate limiting to advanced drive examples (#2301)
This commit is contained in:
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -8,13 +8,15 @@
|
||||
#include "Drivetrain.h"
|
||||
|
||||
void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
|
||||
const auto leftOutput = m_leftPIDController.Calculate(
|
||||
const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
|
||||
const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
|
||||
const double leftOutput = m_leftPIDController.Calculate(
|
||||
m_leftEncoder.GetRate(), speeds.left.to<double>());
|
||||
const auto rightOutput = m_rightPIDController.Calculate(
|
||||
const double rightOutput = m_rightPIDController.Calculate(
|
||||
m_rightEncoder.GetRate(), speeds.right.to<double>());
|
||||
|
||||
m_leftGroup.Set(leftOutput);
|
||||
m_rightGroup.Set(rightOutput);
|
||||
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
|
||||
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
|
||||
}
|
||||
|
||||
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
|
||||
@@ -1,10 +1,11 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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/SlewRateLimiter.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
|
||||
@@ -20,14 +21,16 @@ class Robot : public frc::TimedRobot {
|
||||
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;
|
||||
const auto xSpeed = -m_speedLimiter.Calculate(
|
||||
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) *
|
||||
const auto rot = -m_rotLimiter.Calculate(
|
||||
m_controller.GetX(frc::GenericHID::kRightHand)) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
|
||||
m_drive.Drive(xSpeed, rot);
|
||||
@@ -35,6 +38,12 @@ class Robot : public frc::TimedRobot {
|
||||
|
||||
private:
|
||||
frc::XboxController m_controller{0};
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
// to 1.
|
||||
frc::SlewRateLimiter<units::scalar> m_speedLimiter{3 / 1_s};
|
||||
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
Drivetrain m_drive;
|
||||
};
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -12,6 +12,7 @@
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <units/units.h>
|
||||
@@ -77,4 +78,8 @@ class Drivetrain {
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{GetAngle()};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
// robot!
|
||||
frc::SimpleMotorFeedforward<units::meters> m_feedforward{1_V, 3_V / 1_mps};
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user