Skip to content

Commit

Permalink
Update RobotContainer to specify reference return type
Browse files Browse the repository at this point in the history
  • Loading branch information
bhall-ctre committed Nov 6, 2024
1 parent 3e50ff7 commit 8a4f358
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
6 changes: 3 additions & 3 deletions cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,15 @@ void RobotContainer::ConfigureBindings()
// and Y is defined as to the left according to WPILib convention.
drivetrain.SetDefaultCommand(
// Drivetrain will execute this command periodically
drivetrain.ApplyRequest([this] {
drivetrain.ApplyRequest([this]() -> auto&& {
return drive.WithVelocityX(-joystick.GetLeftY() * MaxSpeed) // Drive forward with negative Y (forward)
.WithVelocityY(-joystick.GetLeftX() * MaxSpeed) // Drive left with negative X (left)
.WithRotationalRate(-joystick.GetRightX() * MaxAngularRate); // Drive counterclockwise with negative X (left)
})
);

joystick.A().WhileTrue(drivetrain.ApplyRequest([this] { return brake; }));
joystick.B().WhileTrue(drivetrain.ApplyRequest([this] {
joystick.A().WhileTrue(drivetrain.ApplyRequest([this]() -> auto&& { return brake; }));
joystick.B().WhileTrue(drivetrain.ApplyRequest([this]() -> auto&& {
return point.WithModuleDirection(frc::Rotation2d{-joystick.GetLeftY(), -joystick.GetLeftX()});
}));

Expand Down
6 changes: 3 additions & 3 deletions cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,15 @@ void RobotContainer::ConfigureBindings()
// and Y is defined as to the left according to WPILib convention.
drivetrain.SetDefaultCommand(
// Drivetrain will execute this command periodically
drivetrain.ApplyRequest([this] {
drivetrain.ApplyRequest([this]() -> auto&& {
return drive.WithVelocityX(-joystick.GetLeftY() * MaxSpeed) // Drive forward with negative Y (forward)
.WithVelocityY(-joystick.GetLeftX() * MaxSpeed) // Drive left with negative X (left)
.WithRotationalRate(-joystick.GetRightX() * MaxAngularRate); // Drive counterclockwise with negative X (left)
})
);

joystick.A().WhileTrue(drivetrain.ApplyRequest([this] { return brake; }));
joystick.B().WhileTrue(drivetrain.ApplyRequest([this] {
joystick.A().WhileTrue(drivetrain.ApplyRequest([this]() -> auto&& { return brake; }));
joystick.B().WhileTrue(drivetrain.ApplyRequest([this]() -> auto&& {
return point.WithModuleDirection(frc::Rotation2d{-joystick.GetLeftY(), -joystick.GetLeftX()});
}));

Expand Down

0 comments on commit 8a4f358

Please sign in to comment.