Add RamseteCommand (#1951)

This commit is contained in:
Oblarg
2019-10-27 00:33:41 -04:00
committed by Peter Johnson
parent 989df1b461
commit 75438ab2ce
20 changed files with 1590 additions and 2 deletions

View File

@@ -0,0 +1,71 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-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 "Robot.h"
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,87 @@
/*----------------------------------------------------------------------------*/
/* 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 "RobotContainer.h"
#include <frc/controller/PIDController.h>
#include <frc/controller/RamseteController.h>
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc/trajectory/Trajectory.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/RamseteCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/button/JoystickButton.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Set up config for trajectory
frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
AutoConstants::kMaxAcceleration);
// Add kinematics to ensure max speed is actually obeyed
config.SetKinematics(DriveConstants::kDriveKinematics);
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
// Pass the config
config);
frc2::RamseteCommand ramseteCommand(
exampleTrajectory, [this]() { return m_drive.GetPose(); },
frc::RamseteController(AutoConstants::kRamseteB,
AutoConstants::kRamseteZeta),
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka,
DriveConstants::kDriveKinematics,
[this] {
return units::meters_per_second_t(m_drive.GetLeftEncoder().GetRate());
},
[this] {
return units::meters_per_second_t(m_drive.GetRightEncoder().GetRate());
},
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
[this](auto left, auto right) {
m_drive.TankDrive(left / 12_V, right / 12_V);
},
{&m_drive});
// no auto
return new frc2::SequentialCommandGroup(
std::move(ramseteCommand),
frc2::InstantCommand([this] { m_drive.TankDrive(0, 0); }, {}));
}

View File

@@ -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. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
#include <units/units.h>
#include <frc/geometry/Rotation2d.h>
#include <frc/kinematics/DifferentialDriveWheelSpeeds.h>
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]},
m_odometry{kDriveKinematics, frc::Pose2d()} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())),
frc::DifferentialDriveWheelSpeeds{
units::meters_per_second_t(m_leftEncoder.GetRate()),
units::meters_per_second_t(m_rightEncoder.GetRate())});
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::TankDrive(double left, double right) {
m_drive.TankDrive(left, right, false);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
}
double DriveSubsystem::GetTurnRate() {
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
}
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
m_odometry.ResetPosition(pose);
}

View File

@@ -0,0 +1,71 @@
/*----------------------------------------------------------------------------*/
/* 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 <units/units.h>
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
const int kLeftMotor1Port = 0;
const int kLeftMotor2Port = 1;
const int kRightMotor1Port = 2;
const int kRightMotor2Port = 3;
const int kLeftEncoderPorts[]{0, 1};
const int kRightEncoderPorts[]{2, 3};
const bool kLeftEncoderReversed = false;
const bool kRightEncoderReversed = true;
const auto kTrackwidth = .6_m;
const frc::DifferentialDriveKinematics kDriveKinematics(kTrackwidth);
const int kEncoderCPR = 1024;
const double kWheelDiameterInches = 6;
const double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
const bool kGyroReversed = true;
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
// These characterization values MUST be determined either experimentally or
// theoretically for *your* robot's drive. The RobotPy Characterization
// Toolsuite provides a convenient tool for obtaining these values for your
// robot.
const auto ks = 1_V;
const auto kv = .8 * 1_V * 1_s / 1_m;
const auto ka = .15 * 1_V * 1_s * 1_s / 1_m;
// Example value only - as above, this must be tuned for your drive!
const double kPDriveVel = .5;
} // namespace DriveConstants
namespace AutoConstants {
const auto kMaxSpeed = 3_mps;
const auto kMaxAcceleration = 3_mps_sq;
// Reasonable baseline values for a RAMSETE follower in units of meters and
// seconds
const double kRamseteB = 2;
const double kRamseteZeta = .7;
} // namespace AutoConstants
namespace OIConstants {
const int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,33 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-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/TimedRobot.h>
#include <frc2/command/Command.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,53 @@
/*----------------------------------------------------------------------------*/
/* 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/XboxController.h>
#include <frc/controller/PIDController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/PIDCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,141 @@
/*----------------------------------------------------------------------------*/
/* 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/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/geometry/Pose2d.h>
#include <frc/kinematics/DifferentialDriveOdometry.h>
#include <frc2/command/SubsystemBase.h>
#include "Constants.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Drives the robot using tank controls. Does not square inputs to enable
* composition with external controllers.
*
* @param left the commanded left output
* @param right the commanded right output
*/
void TankDrive(double left, double right);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* Sets the max output of the drive. Useful for scaling the drive to drive
* more slowly.
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
/**
* Returns the heading of the robot.
*
* @return the robot's heading in degrees, from 180 to 180
*/
double GetHeading();
/**
* Returns the turn rate of the robot.
*
* @return The turn rate of the robot, in degrees per second
*/
double GetTurnRate();
/**
* Returns the currently-estimated pose of the robot.
*
* @return The pose.
*/
frc::Pose2d GetPose();
/**
* Resets the odometry to the specified pose.
*
* @param pose The pose to which to set the odometry.
*/
void ResetOdometry(frc::Pose2d pose);
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
// The gyro sensor
frc::ADXRS450_Gyro m_gyro;
// Odometry class for tracking robot pose
frc::DifferentialDriveOdometry m_odometry;
};