Merge .inc files into headers (#7215)

This commit is contained in:
Tyler Veness
2024-10-15 23:42:57 -07:00
committed by GitHub
parent 40caabea23
commit fad06ae1e7
25 changed files with 913 additions and 1520 deletions

View File

@@ -3,6 +3,8 @@
// the WPILib BSD license file in the root directory of this project.
#include <functional>
#include <memory>
#include <utility>
#include <frc/Timer.h>
#include <frc/controller/HolonomicDriveController.h>
@@ -91,7 +93,15 @@ class SwerveControllerCommand
std::function<frc::Rotation2d()> desiredRotation,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
output,
Requirements requirements = {});
Requirements requirements = {})
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(std::move(desiredRotation)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
/**
* Constructs a new SwerveControllerCommand that when executed will follow the
@@ -129,7 +139,14 @@ class SwerveControllerCommand
frc::ProfiledPIDController<units::radians> thetaController,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
output,
Requirements requirements = {});
Requirements requirements = {})
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_outputStates(output) {
this->AddRequirements(requirements);
}
/**
* Constructs a new SwerveControllerCommand that when executed will follow the
@@ -159,7 +176,15 @@ class SwerveControllerCommand
std::function<frc::Rotation2d()> desiredRotation,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
output,
Requirements requirements = {});
Requirements requirements = {})
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(std::move(controller)),
m_desiredRotation(std::move(desiredRotation)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
/**
* Constructs a new SwerveControllerCommand that when executed will follow the
@@ -191,15 +216,41 @@ class SwerveControllerCommand
frc::HolonomicDriveController controller,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
output,
Requirements requirements = {});
Requirements requirements = {})
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(std::move(controller)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
void Initialize() override;
void Initialize() override {
if (m_desiredRotation == nullptr) {
m_desiredRotation = [&] {
return m_trajectory.States().back().pose.Rotation();
};
}
m_timer.Restart();
}
void Execute() override;
void Execute() override {
auto curTime = m_timer.Get();
auto m_desiredState = m_trajectory.Sample(curTime);
void End(bool interrupted) override;
auto targetChassisSpeeds =
m_controller.Calculate(m_pose(), m_desiredState, m_desiredRotation());
auto targetModuleStates =
m_kinematics.ToSwerveModuleStates(targetChassisSpeeds);
bool IsFinished() override;
m_outputStates(targetModuleStates);
}
void End(bool interrupted) override { m_timer.Stop(); }
bool IsFinished() override {
return m_timer.HasElapsed(m_trajectory.TotalTime());
}
private:
frc::Trajectory m_trajectory;
@@ -215,6 +266,5 @@ class SwerveControllerCommand
units::second_t m_prevTime;
frc::Rotation2d m_finalRotation;
};
} // namespace frc2
#include "SwerveControllerCommand.inc"
} // namespace frc2

View File

@@ -1,114 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <functional>
#include <memory>
#include <utility>
#include "frc2/command/SwerveControllerCommand.h"
namespace frc2 {
template <size_t NumModules>
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc::PIDController xController, frc::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
std::function<frc::Rotation2d()> desiredRotation,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
Requirements requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(std::move(desiredRotation)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
template <size_t NumModules>
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc::PIDController xController, frc::PIDController yController,
frc::ProfiledPIDController<units::radians> thetaController,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
Requirements requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_outputStates(output) {
this->AddRequirements(requirements);
}
template <size_t NumModules>
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc::HolonomicDriveController controller,
std::function<frc::Rotation2d()> desiredRotation,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
Requirements requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(std::move(controller)),
m_desiredRotation(std::move(desiredRotation)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
template <size_t NumModules>
SwerveControllerCommand<NumModules>::SwerveControllerCommand(
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
frc::SwerveDriveKinematics<NumModules> kinematics,
frc::HolonomicDriveController controller,
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> output,
Requirements requirements)
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(std::move(controller)),
m_outputStates(output) {
this->AddRequirements(requirements);
}
template <size_t NumModules>
void SwerveControllerCommand<NumModules>::Initialize() {
if (m_desiredRotation == nullptr) {
m_desiredRotation = [&] {
return m_trajectory.States().back().pose.Rotation();
};
}
m_timer.Restart();
}
template <size_t NumModules>
void SwerveControllerCommand<NumModules>::Execute() {
auto curTime = m_timer.Get();
auto m_desiredState = m_trajectory.Sample(curTime);
auto targetChassisSpeeds =
m_controller.Calculate(m_pose(), m_desiredState, m_desiredRotation());
auto targetModuleStates =
m_kinematics.ToSwerveModuleStates(targetChassisSpeeds);
m_outputStates(targetModuleStates);
}
template <size_t NumModules>
void SwerveControllerCommand<NumModules>::End(bool interrupted) {
m_timer.Stop();
}
template <size_t NumModules>
bool SwerveControllerCommand<NumModules>::IsFinished() {
return m_timer.HasElapsed(m_trajectory.TotalTime());
}
} // namespace frc2