mirror of
https://github.com/Team4388/Robot-Essentials.git
synced 2026-06-09 08:48:02 -06:00
Setup Motors and Controllers
This commit is contained in:
@@ -7,6 +7,10 @@
|
||||
|
||||
package frc4388.robot;
|
||||
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import frc4388.utility.controller.IHandController;
|
||||
import frc4388.utility.controller.XboxController;
|
||||
|
||||
/**
|
||||
* This class is the glue that binds the controls on the physical operator
|
||||
* interface to the commands and command groups that allow control of the robot.
|
||||
@@ -39,4 +43,35 @@ public class OI {
|
||||
// Start the command when the button is released and let it run the command
|
||||
// until it is finished as determined by it's isFinished method.
|
||||
// button.whenReleased(new ExampleCommand());
|
||||
|
||||
private static OI instance;
|
||||
|
||||
private static XboxController m_driverXbox;
|
||||
private static XboxController m_operatorXbox;
|
||||
|
||||
public OI() {
|
||||
m_driverXbox = new XboxController(RobotMap.XBOX_DRIVER_ID);
|
||||
m_operatorXbox = new XboxController(RobotMap.XBOX_OPERATOR_ID);
|
||||
}
|
||||
|
||||
public static OI getInstance() {
|
||||
if(instance == null) {
|
||||
instance = new OI();
|
||||
}
|
||||
return instance;
|
||||
}
|
||||
|
||||
public IHandController getDriverController() {
|
||||
return m_driverXbox;
|
||||
}
|
||||
|
||||
public IHandController getOperatorController()
|
||||
{
|
||||
return m_operatorXbox;
|
||||
}
|
||||
|
||||
public Joystick getOperatorJoystick()
|
||||
{
|
||||
return m_operatorXbox.getJoyStick();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
|
||||
package frc4388.robot;
|
||||
|
||||
import frc4388.utility.controller.XboxController;
|
||||
|
||||
/**
|
||||
* The RobotMap is a mapping from the ports sensors and actuators are wired into
|
||||
* to a variable name. This provides flexibility changing wiring, makes checking
|
||||
@@ -24,5 +26,16 @@ public class RobotMap {
|
||||
// public static int rangefinderPort = 1;
|
||||
// public static int rangefinderModule = 1;
|
||||
|
||||
/* Xbox Controllers */
|
||||
public static final int XBOX_DRIVER_ID = 0;
|
||||
public static final int XBOX_OPERATOR_ID = 1;
|
||||
|
||||
/* Blinkin LED Strip */
|
||||
public static final int LED_SPARK_ID = 0;
|
||||
|
||||
/* Drive Train */
|
||||
public static final int DRIVE_LEFT_FRONT_CAN_ID = 2;
|
||||
public static final int DRIVE_RIGHT_FRONT_CAN_ID = 4;
|
||||
public static final int DRIVE_LEFT_BACK_CAN_ID = 3;
|
||||
public static final int DRIVE_RIGHT_BACK_CAN_ID = 5;
|
||||
}
|
||||
|
||||
@@ -7,7 +7,18 @@
|
||||
|
||||
package frc4388.robot.subsystems;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.Faults;
|
||||
import com.ctre.phoenix.motorcontrol.InvertType;
|
||||
import com.ctre.phoenix.motorcontrol.NeutralMode;
|
||||
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import edu.wpi.first.wpilibj.Talon;
|
||||
import edu.wpi.first.wpilibj.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import frc4388.robot.RobotMap;
|
||||
import frc4388.robot.Robot;
|
||||
import frc4388.utility.controller.XboxController;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
@@ -16,6 +27,41 @@ public class Drive extends Subsystem {
|
||||
// Put methods for controlling this subsystem
|
||||
// here. Call these from Commands.
|
||||
|
||||
WPI_TalonSRX m_leftFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_FRONT_CAN_ID);
|
||||
WPI_TalonSRX m_rightFrontMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_FRONT_CAN_ID);
|
||||
WPI_TalonSRX m_leftBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_LEFT_BACK_CAN_ID);
|
||||
WPI_TalonSRX m_rightBackMotor = new WPI_TalonSRX(RobotMap.DRIVE_RIGHT_BACK_CAN_ID);
|
||||
|
||||
DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor);
|
||||
|
||||
public Drive(){
|
||||
/* factory default values */
|
||||
m_leftFrontMotor.configFactoryDefault();
|
||||
m_rightFrontMotor.configFactoryDefault();
|
||||
m_leftBackMotor.configFactoryDefault();
|
||||
m_rightBackMotor.configFactoryDefault();
|
||||
|
||||
/* set back motors as followers */
|
||||
m_leftBackMotor.follow(m_leftFrontMotor);
|
||||
m_rightBackMotor.follow(m_rightFrontMotor);
|
||||
|
||||
/* set neutral mode */
|
||||
m_leftFrontMotor.setNeutralMode(NeutralMode.Brake);
|
||||
m_rightFrontMotor.setNeutralMode(NeutralMode.Brake);
|
||||
m_leftFrontMotor.setNeutralMode(NeutralMode.Brake);
|
||||
m_rightFrontMotor.setNeutralMode(NeutralMode.Brake);
|
||||
|
||||
/* flip input so forward becomes back, etc */
|
||||
m_leftFrontMotor.setInverted(false);
|
||||
m_rightFrontMotor.setInverted(false);
|
||||
m_leftBackMotor.setInverted(InvertType.FollowMaster);
|
||||
m_rightBackMotor.setInverted(InvertType.FollowMaster);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initDefaultCommand() {
|
||||
// Set the default command for a subsystem here.
|
||||
|
||||
Reference in New Issue
Block a user