Skip to content

Commit

Permalink
working auto changes
Browse files Browse the repository at this point in the history
  • Loading branch information
AntarcticaByToto authored and mray190 committed Jun 14, 2021
1 parent 46841cf commit e88c51e
Showing 1 changed file with 43 additions and 8 deletions.
51 changes: 43 additions & 8 deletions Competition/src/main/cpp/ValorAuto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,11 @@ ValorAuto::ValorAuto(Drivetrain* _drivetrain, Intake* _intake, Shooter* _shooter

// SHOOT 3 MOVE 5 OFFSET POSITION
auto traj_move5_offset = frc::TrajectoryGenerator::GenerateTrajectory(frc::Pose2d(0_m, 0_m,frc::Rotation2d(0_deg)),
{ frc::Translation2d(2_m, 0.6_m)},
frc::Pose2d(5.6_m, 1_m, frc::Rotation2d(0_deg)),
{ frc::Translation2d(2_m, 0.5_m)},
frc::Pose2d(5.6_m, 0.9_m, frc::Rotation2d(0_deg)),
kTrajectoryConfigForward);

auto traj_reverse_move5_offset = frc::TrajectoryGenerator::GenerateTrajectory(frc::Pose2d(5.6_m, 1_m, frc::Rotation2d(0_deg)),
auto traj_reverse_move5_offset = frc::TrajectoryGenerator::GenerateTrajectory(frc::Pose2d(5.6_m, 0.9_m, frc::Rotation2d(0_deg)),
{ },
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
kTrajectoryConfigReverse);
Expand Down Expand Up @@ -104,6 +104,39 @@ ValorAuto::ValorAuto(Drivetrain* _drivetrain, Intake* _intake, Shooter* _shooter
[&] (auto left, auto right) { drivetrain->TankDriveVolts(left, right); },
{drivetrain});

frc2::RamseteCommand cmd_move5move5_first(traj_move5,
[&] () { return drivetrain->GetPose(); },
frc::RamseteController(RamseteConstants::kRamseteB, RamseteConstants::kRamseteZeta),
kSimpleMotorFeedforward,
kDriveKinematics,
[&] { return drivetrain->GetWheelSpeeds(); },
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
[&] (auto left, auto right) { drivetrain->TankDriveVolts(left, right); },
{drivetrain});

frc2::RamseteCommand cmd_reverse_move5move5(traj_reverse_move5,
[&] () { return drivetrain->GetPose(); },
frc::RamseteController(RamseteConstants::kRamseteB, RamseteConstants::kRamseteZeta),
kSimpleMotorFeedforward,
kDriveKinematics,
[&] { return drivetrain->GetWheelSpeeds(); },
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
[&] (auto left, auto right) { drivetrain->TankDriveVolts(left, right); },
{drivetrain});

frc2::RamseteCommand cmd_move5move5_second(traj_move5,
[&] () { return drivetrain->GetPose(); },
frc::RamseteController(RamseteConstants::kRamseteB, RamseteConstants::kRamseteZeta),
kSimpleMotorFeedforward,
kDriveKinematics,
[&] { return drivetrain->GetWheelSpeeds(); },
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
frc2::PIDController(RamseteConstants::kPDriveVel, 0, 0),
[&] (auto left, auto right) { drivetrain->TankDriveVolts(left, right); },
{drivetrain});

frc2::SequentialCommandGroup *shoot3move5 = new frc2::SequentialCommandGroup();
shoot3move5->AddCommands(cmd_spoolUp,
frc2::WaitCommand((units::second_t)1.5),
Expand All @@ -122,7 +155,8 @@ ValorAuto::ValorAuto(Drivetrain* _drivetrain, Intake* _intake, Shooter* _shooter
autos["Shoot3Move5"] = shoot3move5;

frc2::SequentialCommandGroup *shoot3move5Offset = new frc2::SequentialCommandGroup();
shoot3move5Offset->AddCommands(cmd_spoolUp,
shoot3move5Offset->AddCommands(cmd_track,
cmd_spoolUp,
frc2::WaitCommand((units::second_t)1.5),
cmd_intake,
cmd_shoot,
Expand All @@ -141,6 +175,7 @@ ValorAuto::ValorAuto(Drivetrain* _drivetrain, Intake* _intake, Shooter* _shooter
frc2::SequentialCommandGroup *shoot3 = new frc2::SequentialCommandGroup();
shoot3->AddCommands(cmd_spoolUp,
frc2::WaitCommand((units::second_t)2),
cmd_intake,
cmd_shoot,
frc2::WaitCommand((units::second_t)3),
cmd_stopShoot,
Expand All @@ -154,15 +189,15 @@ ValorAuto::ValorAuto(Drivetrain* _drivetrain, Intake* _intake, Shooter* _shooter
cmd_shoot,
frc2::WaitCommand((units::second_t)1.5),
cmd_stopShoot,
std::move(cmd_move5),
std::move(cmd_reverse_move5),
std::move(cmd_move5move5_first),
std::move(cmd_reverse_move5move5),
cmd_track,
frc2::WaitCommand((units::second_t)1),
frc2::WaitCommand((units::second_t)1),
cmd_shoot,
frc2::WaitCommand((units::second_t)2),
cmd_stopShoot,
cmd_spoolDown,
std::move(cmd_move5));
std::move(cmd_move5move5_second));
autos["Shoot3Move5Move5"] = shoot3move5move5;
}

Expand Down

0 comments on commit e88c51e

Please sign in to comment.