Setup Motors and Controllers

This commit is contained in:
HFocus
2019-08-07 18:48:49 -06:00
parent 4c90f039ef
commit 7a19b683f6
4 changed files with 181 additions and 0 deletions
@@ -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.