From 8a4f3583f7ed44244a8ce74898608c7f89176b5f Mon Sep 17 00:00:00 2001 From: Benjamin Hall Date: Wed, 6 Nov 2024 16:28:32 -0500 Subject: [PATCH] Update RobotContainer to specify reference return type --- cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp | 6 +++--- cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp b/cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp index ba581485..2dffade8 100644 --- a/cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp +++ b/cpp/SwerveWithChoreo/src/main/cpp/RobotContainer.cpp @@ -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()}); })); diff --git a/cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp b/cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp index 1a4ce824..1ffbfbd6 100644 --- a/cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp +++ b/cpp/SwerveWithPathPlanner/src/main/cpp/RobotContainer.cpp @@ -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()}); }));