Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Code for claw mech. RobotContainer updated with button bindings and s… #10

Closed
wants to merge 9 commits into from
17 changes: 17 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,12 @@
import frc.robot.commands.elevator.ElevatorUpCommand;
import frc.robot.commands.elevator.ElevatorDownCommand;
import frc.robot.commands.elevator.ElevatorStopCommand;
import frc.robot.subsystems.ClawSubsystem.ClawSubsystem;
import frc.robot.subsystems.elevator.ElevatorSubsystem;
import frc.robot.subsystems.tank.TankSubsystem;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj.Solenoid;

/**
* This class is where the bulk of the robot should be declared. Since
Expand All @@ -39,6 +42,7 @@ public class RobotContainer {

// Subsystems
private final TankSubsystem tankSubsystem;
private final ClawSubsystem clawSubsystem;

// Controllers
private XboxController controlXbox = new XboxController(0);
Expand Down Expand Up @@ -68,6 +72,7 @@ public RobotContainer() {

// Instantiate subsystems
tankSubsystem = new TankSubsystem();
clawSubsystem = new ClawSubsystem();

// Instantiate commands
tankCommand = new DriveTankCommand(tankSubsystem, 0, 0);
Expand Down Expand Up @@ -96,6 +101,18 @@ private void controllerBindings() {
// Set the drive powers based on which controller is being used
if (isXbox) {
tankSubsystem.setCarDrivePowers(-controlXbox.getY(Hand.kLeft), controlXbox.getX(Hand.kRight));
if(controlXbox.getAButtonPressed()){
clawSubsystem.openClaw();
}
if(controlXbox.getBButtonPressed()){
clawSubsystem.openClaw();
}
if(controlXbox.getXButtonPressed()){
clawSubsystem.liftClaw();
}
if(controlXbox.getYButtonPressed()){
clawSubsystem.lowerClaw();
}
} else {
tankSubsystem.setTankDrivePowers(-joystickLeft.getY(), -joystickRight.getY());
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
package frc.robot.subsystems.ClawSubsystem;

import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj.Solenoid;

import com.ctre.phoenix.motorcontrol.ControlMode;

public class ClawSubsystem extends SubsystemBase{
private TalonSRX motor1;
private Solenoid pfft1;

public ClawSubsystem() {

CommandScheduler.getInstance().registerSubsystem(this);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is a line in the super constructor, which according to Kevin, is already called. So I think we can get away with not having this line


motor1 = new TalonSRX(0);
pfft1 = new Solenoid(1);
}

@Override
public void periodic() {
// This method will be called once per scheduler run

}

@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run during simulation
}

public void openClaw(){
motor1.set(ControlMode.PercentOutput, .5);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think that we should stick to our state system, in that we should have states that are public field variable (e.g. "public boolean openClaw"), and then take action in periodic() based on that field variable. same applies for lift methods.

On top of that, we should probably use encoders and run the motor until it stops moving (rate of change of encoder reading is basically 0), rather than keeping it powered. We have a high chance of burning out motors if we just set power.

}

public void closeClaw(){
motor1.set(ControlMode.PercentOutput, -.5);
}

public void liftClaw(){
pfft1.set(true);
}

public void lowerClaw(){
pfft1.set(false);
motor1.set(ControlMode.PercentOutput, -.5);
}
}