[examples] Remove redundant MotorControl example (#4837)

The MotorControlEncoder had the exact same content, with the addition of an encoder. No point in having both examples.
This commit is contained in:
Starlight220
2022-12-26 21:27:20 +02:00
committed by GitHub
parent 1cbebaa2f7
commit 4534e75787
7 changed files with 47 additions and 164 deletions

View File

@@ -229,20 +229,7 @@
"commandversion": 2
},
{
"name": "Motor Controller",
"description": "Demonstrate controlling a single motor with a joystick",
"tags": [
"Actuators",
"Joystick",
"Robot and Motor"
],
"foldername": "motorcontrol",
"gradlebase": "java",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "Motor Control With Encoder",
"name": "Motor Control",
"description": "Demonstrate controlling a single motor with a Joystick and displaying the net movement of the motor using an encoder.",
"tags": [
"Robot and Motor",
@@ -252,7 +239,7 @@
"Joystick",
"Complete List"
],
"foldername": "motorcontrolencoder",
"foldername": "motorcontrol",
"gradlebase": "java",
"mainclass": "Main",
"commandversion": 2

View File

@@ -4,10 +4,12 @@
package edu.wpi.first.wpilibj.examples.motorcontrol;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* This sample program shows how to control a motor using a joystick. In the operator control part
@@ -15,18 +17,37 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
*
* <p>Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1
* making it easy to work together.
*
* <p>In addition, the encoder value of an encoder connected to ports 0 and 1 is consistently sent
* to the Dashboard.
*/
public class Robot extends TimedRobot {
private static final int kMotorPort = 0;
private static final int kJoystickPort = 0;
private static final int kEncoderPortA = 0;
private static final int kEncoderPortB = 1;
private MotorController m_motor;
private Joystick m_joystick;
private Encoder m_encoder;
@Override
public void robotInit() {
m_motor = new PWMSparkMax(kMotorPort);
m_joystick = new Joystick(kJoystickPort);
m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
// Use SetDistancePerPulse to set the multiplier for GetDistance
// This is set up assuming a 6 inch wheel with a 360 CPR encoder.
m_encoder.setDistancePerPulse((Math.PI * 6) / 360.0);
}
/*
* The RobotPeriodic function is called every control packet no matter the
* robot mode.
*/
@Override
public void robotPeriodic() {
SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
}
@Override

View File

@@ -1,25 +0,0 @@
// 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 edu.wpi.first.wpilibj.examples.motorcontrolencoder;
import edu.wpi.first.wpilibj.RobotBase;
/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
* you are doing, do not modify this file except to change the parameter class to the startRobot
* call.
*/
public final class Main {
private Main() {}
/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
}

View File

@@ -1,57 +0,0 @@
// 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 edu.wpi.first.wpilibj.examples.motorcontrolencoder;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* This sample program shows how to control a motor using a joystick. In the operator control part
* of the program, the joystick is read and the value is written to the motor.
*
* <p>Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1
* making it easy to work together.
*
* <p>In addition, the encoder value of an encoder connected to ports 0 and 1 is consistently sent
* to the Dashboard.
*/
public class Robot extends TimedRobot {
private static final int kMotorPort = 0;
private static final int kJoystickPort = 0;
private static final int kEncoderPortA = 0;
private static final int kEncoderPortB = 1;
private MotorController m_motor;
private Joystick m_joystick;
private Encoder m_encoder;
@Override
public void robotInit() {
m_motor = new PWMSparkMax(kMotorPort);
m_joystick = new Joystick(kJoystickPort);
m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
// Use SetDistancePerPulse to set the multiplier for GetDistance
// This is set up assuming a 6 inch wheel with a 360 CPR encoder.
m_encoder.setDistancePerPulse((Math.PI * 6) / 360.0);
}
/*
* The RobotPeriodic function is called every control packet no matter the
* robot mode.
*/
@Override
public void robotPeriodic() {
SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
}
@Override
public void teleopPeriodic() {
m_motor.set(m_joystick.getY());
}
}