Skip to content
This repository has been archived by the owner on Nov 10, 2024. It is now read-only.

Commit

Permalink
Fransa cezaevinden selamlar
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Feb 13, 2024
1 parent 8315c6d commit 42425d9
Show file tree
Hide file tree
Showing 15 changed files with 355 additions and 258 deletions.
85 changes: 72 additions & 13 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -1,19 +1,78 @@
// 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.

package frc.robot;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
* constants. This class should not be used for any other purpose. All constants should be declared
* globally (i.e. public static). Do not put anything functional in this class.
*
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static class OperatorConstants {
public static final int kDriverControllerPort = 0;

public static class ports {
public static final int intake_motor_1 = 0;
public static final int intake_motor_2 = 0;
public static final int shooter_motor_1 = 0;
public static final int shooter_motor_2 = 0;

}

public static class controller {
public static final int controller = 0;
}

/*
___ __ _ _ _ _____ _ _
/ __|___ _ _ / _(_)__ _ _ _ _ _ __ _| |_(_)___ _ _ |_ _|_ _| |__| |___
| (__/ _ \ ' \| _| / _` | || | '_/ _` | _| / _ \ ' \ | |/ _` | '_ \ / -_)
\___\___/_||_|_| |_\__, |\_,_|_| \__,_|\__|_\___/_||_| |_|\__,_|_.__/_\___|
|___/
*/

public static class values {

public static class intake {
public static final double GetNoteValue = 1;
public static final double PidIntakeTolerance = 5;
public static final double PidIntakeKP = 1;
public static final double PidIntakeKI = 0;
public static final double PidIntakeKD = 0;
}



public static class shooter {
public static final double AngleMotorOpenLoopRampRate = 0.5;
public static final double PidShooterAngleTolerance = 5;
public static final double PidShooterAngleKP = 1;
public static final double PidShooterAngleKI = 0;
public static final double PidShooterAngleKD = 0;

public static final double PidShooterShootKP = 1;
public static final double PidShooterShootKI = 0;
public static final double PidShooterShootKD = 0;
public static final double PidShooterRPMTolerance = 5;

}


public static class positions {

public static final double FeedingPositionIntake = 1;
public static final double FeedingPositionShooter = 1;

}




public static class feeder {

public static final double FeederForwardSpeed = 0.7;
public static final double FeederBackwardSpeed = -0.7;

}






}

}
40 changes: 4 additions & 36 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,96 +8,64 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;

/**
* The VM is configured to automatically run this class, and to call the functions corresponding to
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
* the package after creating this project, you must also update the build.gradle file in the
* project.
*/

public class Robot extends TimedRobot {
private Command m_autonomousCommand;

private RobotContainer m_robotContainer;

/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.

m_robotContainer = new RobotContainer();
}

/**
* This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
* that you want ran during disabled, autonomous, teleoperated and test.
*
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
* SmartDashboard integrated updating.
*/

@Override
public void robotPeriodic() {
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
// commands, running already-scheduled commands, removing finished or interrupted commands,
// and running subsystem periodic() methods. This must be called from the robot's periodic
// block in order for anything in the Command-based framework to work.
CommandScheduler.getInstance().run();
}

/** This function is called once each time the robot enters Disabled mode. */
@Override
public void disabledInit() {}

@Override
public void disabledPeriodic() {}

/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */

@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();

// schedule the autonomous command (example)
if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
}
}

/** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {}

@Override
public void teleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
}

/** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}

@Override
public void testInit() {
// Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll();
}

/** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}

/** This function is called once when the robot is first started up. */
@Override
public void simulationInit() {}

/** This function is called periodically whilst in simulation. */
@Override
public void simulationPeriodic() {}
}
60 changes: 12 additions & 48 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -1,63 +1,27 @@
// 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.

package frc.robot;

import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.Autos;
import frc.robot.commands.ExampleCommand;
import frc.robot.subsystems.ExampleSubsystem;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
* subsystems, commands, and trigger mappings) should be declared here.
*/
public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
import frc.robot.Constants.controller;

// Replace with CommandPS4Controller or CommandJoystick if needed
private final CommandXboxController m_driverController =
new CommandXboxController(OperatorConstants.kDriverControllerPort);
public class RobotContainer {
XboxController controller = new XboxController(Constants.controller.controller);


/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
// Configure the trigger bindings

configureBindings();

}

/**
* Use this method to define your trigger->command mappings. Triggers can be created via the
* {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary
* predicate, or via the named factories in {@link
* edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link
* CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller
* PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight
* joysticks}.
*/

private void configureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
new Trigger(m_exampleSubsystem::exampleCondition)
.onTrue(new ExampleCommand(m_exampleSubsystem));

// Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
// cancelling on release.
m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
}

/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
*/

public Command getAutonomousCommand() {
// An example command will be run in autonomous
return Autos.exampleAuto(m_exampleSubsystem);
return null;
}
}
20 changes: 0 additions & 20 deletions src/main/java/frc/robot/commands/Autos.java

This file was deleted.

43 changes: 0 additions & 43 deletions src/main/java/frc/robot/commands/ExampleCommand.java

This file was deleted.

28 changes: 15 additions & 13 deletions src/main/java/frc/robot/commands/Intake/PidIntakeCommand.java
Original file line number Diff line number Diff line change
@@ -1,32 +1,34 @@
package frc.robot.commands;
package frc.robot.commands.Intake;

import java.util.function.DoubleSupplier;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.Constants;
import frc.robot.subsystems.IntakeSubsystem;


public class PidIntakeCommand extends PIDCommand {
double tolerance = 5;

public PidIntakeCommand(IntakeSubsystem m_intake, double position) {
super(

new PIDController(1, 0, 0),

() -> m_intake.getEncoderOutput(),

new PIDController(Constants.values.intake.PidIntakeKP,
Constants.values.intake.PidIntakeKI,
Constants.values.intake.PidIntakeKD),
() -> m_intake.getMappedOutput(),
() -> position,

output -> {
if (position > m_intake.getEncoderOutput()) {
m_intake.intakeMotorOutput(-output);;
} else if (position < m_intake.getEncoderOutput()) {
m_intake.intakeMotorOutput(output);;
if (position > m_intake.getMappedOutput()) {
m_intake.NewIntakeMotorOutput(-output);
}

else if (position < m_intake.getMappedOutput()) {
m_intake.NewIntakeMotorOutput(output);
}

});

addRequirements(m_intake);
getController().setTolerance(Constants.values.intake.PidIntakeTolerance);
}


Expand Down
Loading

0 comments on commit 42425d9

Please sign in to comment.