Definition at line 47 of file RobotContainer.h.
RobotContainer::RobotContainer |
( |
| ) |
|
void RobotContainer::Periodic |
( |
| ) |
|
void RobotContainer::ZeroDrive |
( |
| ) |
|
Definition at line 84 of file RobotContainer.cpp.
References DriveSubsystem::Drive(), and m_drive.
87 units::meters_per_second_t(0.0),
88 units::radians_per_second_t(0.0),
false);
void Drive(meters_per_second_t xSpeed, meters_per_second_t ySpeed, radians_per_second_t rot, bool fieldRelative)
frc2::Command * RobotContainer::GetAutonomousCommand |
( |
AutoPath |
path | ) |
|
Definition at line 91 of file RobotContainer.cpp.
References GetSwerveCommand(), kEx1, kEx2, kEx3, kEx4, left3, mid0, mid5, right2, and ZeroDrive().
96 return new frc2::SequentialCommandGroup(
98 frc2::ParallelRaceGroup(
102 frc2::InstantCommand(
111 return new frc2::SequentialCommandGroup(
113 frc2::InstantCommand(
122 return new frc2::SequentialCommandGroup(
124 frc2::ParallelRaceGroup(
128 frc2::InstantCommand(
137 return new frc2::SequentialCommandGroup(
138 frc2::ParallelRaceGroup(
142 frc2::InstantCommand(
151 return new frc2::SequentialCommandGroup(
152 frc2::InstantCommand(
frc2::SwerveControllerCommand2< DriveConstants::kNumSwerveModules > GetSwerveCommand(double path[][6], int length, bool primaryPath)
void RobotContainer::SetDefaultCommands |
( |
| ) |
|
|
private |
X and Y are deadzoned twice - once individually with very small values, then another with a pinwheel deadzone
Definition at line 32 of file RobotContainer.cpp.
References Util::Deadzone(), DriveSubsystem::Drive(), OIConstants::kDeadzoneRot, OIConstants::kDeadzoneX, OIConstants::kDeadzoneXY, OIConstants::kDeadzoneY, DriveConstants::kDriveAngularSpeed, AutoConstants::kMaxSpeed, m_drive, m_fieldRelative, and m_primaryController.
34 m_drive.SetDefaultCommand(frc2::RunCommand(
49 units::meters_per_second_t(yInput * AutoConstants::kMaxSpeed),
void Drive(meters_per_second_t xSpeed, meters_per_second_t ySpeed, radians_per_second_t rot, bool fieldRelative)
constexpr double kDeadzoneXY
frc::XboxController m_primaryController
constexpr double kDeadzoneY
constexpr double kDeadzoneX
static double Deadzone(double inputValue, double deadzone)
If an inputValue is smaller than its deadzone, returns 0, otherwise returns the inputValue.
constexpr double kDeadzoneRot
constexpr auto kDriveAngularSpeed
void RobotContainer::ConfigureButtonBindings |
( |
| ) |
|
|
private |
Definition at line 161 of file RobotContainer.cpp.
References convertArrayToTrajectory(), DriveSubsystem::GetPose(), DriveSubsystem::kDriveKinematics, AutoConstants::kDThetaController, AutoConstants::kDXController, AutoConstants::kDYController, AutoConstants::kPThetaController, AutoConstants::kPXController, AutoConstants::kPYController, AutoConstants::kThetaControllerConstraints, m_drive, DriveSubsystem::ResetOdometry(), and DriveSubsystem::SetModuleStates().
165 frc::ProfiledPIDController<units::radians> thetaController{
169 thetaController.EnableContinuousInput(units::radian_t(-wpi::math::pi), units::radian_t(wpi::math::pi));
186 return swerveControllerCommand;
constexpr double kDThetaController
constexpr double kPYController
const frc::TrapezoidProfile< units::radians >::Constraints kThetaControllerConstraints
frc::Trajectory convertArrayToTrajectory(double a[][6], int length)
constexpr double kPThetaController
void ResetOdometry(Pose2d pose)
constexpr double kDXController
constexpr double kPXController
constexpr double kDYController
void SetModuleStates(SwerveModuleStates desiredStates)
Sets the drive SpeedControllers to a power from -1 to 1.
SwerveDriveKinematics< kNumSwerveModules > kDriveKinematics
The kinematics object converts inputs into 4 individual swerve module turn angle and wheel speeds...
frc::Trajectory RobotContainer::convertArrayToTrajectory |
( |
double |
a[][6], |
|
|
int |
length |
|
) |
| |
|
private |
Definition at line 190 of file RobotContainer.cpp.
192 std::vector<frc::Trajectory::State> states;
193 printf(
"Converting array...");
194 for (
int i = 0; i < length; i++)
196 printf(
"looping through timestamps...");
198 a[i][0] * 1_s, a[i][1] * 1_mps, a[i][2] * 1_mps_sq,
199 frc::Pose2d(a[i][3] * 1_m, a[i][4] * -1.0 * 1_m, a[i][5] * -1.0 * 1_deg), curvature_t(0)
202 printf(
"Finished looping, returning Trajectory");
203 return frc::Trajectory(states);
void RobotContainer::PrintTrajectory |
( |
frc::Trajectory & |
trajectory | ) |
|
|
private |
Definition at line 206 of file RobotContainer.cpp.
208 for (
auto &state:trajectory.States())
210 double time = state.t.to<
double>();
211 double x = state.pose.X().to<
double>();
212 double y = state.pose.Y().to<
double>();
213 printf(
"%.3f, %.3f, %.3f\n", time, x, y);
frc::SendableChooser<AutoPath> RobotContainer::m_chooser |
Gyro RobotContainer::m_gyro |
|
private |
bool RobotContainer::m_fieldRelative = true |
|
private |
The documentation for this class was generated from the following files: