diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp index 614ad0afac..7a4325f371 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp @@ -2,9 +2,13 @@ // 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. +#include + +#include #include #include #include +#include /** * This sample program shows how to control a motor using a joystick. In the @@ -13,14 +17,32 @@ * * Joystick analog values range from -1 to 1 and motor controller inputs as * range from -1 to 1 making it easy to work together. + * + * In addition, the encoder value of an encoder connected to ports 0 and 1 is + * consistently sent to the Dashboard. */ class Robot : public frc::TimedRobot { public: void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); } + /* + * The RobotPeriodic function is called every control packet no matter the + * robot mode. + */ + void RobotPeriodic() override { + frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance()); + } + + void RobotInit() override { + // 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((std::numbers::pi * 6) / 360.0); + } + private: frc::Joystick m_stick{0}; frc::PWMSparkMax m_motor{0}; + frc::Encoder m_encoder{0, 1}; }; #ifndef RUNNING_FRC_TESTS diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp deleted file mode 100644 index 7a4325f371..0000000000 --- a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp +++ /dev/null @@ -1,52 +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. - -#include - -#include -#include -#include -#include -#include - -/** - * 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. - * - * Joystick analog values range from -1 to 1 and motor controller inputs as - * range from -1 to 1 making it easy to work together. - * - * In addition, the encoder value of an encoder connected to ports 0 and 1 is - * consistently sent to the Dashboard. - */ -class Robot : public frc::TimedRobot { - public: - void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); } - - /* - * The RobotPeriodic function is called every control packet no matter the - * robot mode. - */ - void RobotPeriodic() override { - frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance()); - } - - void RobotInit() override { - // 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((std::numbers::pi * 6) / 360.0); - } - - private: - frc::Joystick m_stick{0}; - frc::PWMSparkMax m_motor{0}; - frc::Encoder m_encoder{0, 1}; -}; - -#ifndef RUNNING_FRC_TESTS -int main() { - return frc::StartRobot(); -} -#endif diff --git a/wpilibcExamples/src/main/cpp/examples/examples.json b/wpilibcExamples/src/main/cpp/examples/examples.json index 499a2fb62d..aaec45def6 100644 --- a/wpilibcExamples/src/main/cpp/examples/examples.json +++ b/wpilibcExamples/src/main/cpp/examples/examples.json @@ -1,19 +1,6 @@ [ { - "name": "Motor Controller", - "description": "Demonstrate controlling a single motor with a Joystick.", - "tags": [ - "Robot and Motor", - "Actuators", - "Joystick", - "Complete List" - ], - "foldername": "MotorControl", - "gradlebase": "cpp", - "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", @@ -23,7 +10,7 @@ "Joystick", "Complete List" ], - "foldername": "MotorControlEncoder", + "foldername": "MotorControl", "gradlebase": "cpp", "commandversion": 2 }, diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json index 1b76a28a23..01f79e7745 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json @@ -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 diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java index 0647dd990b..82ced20919 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java @@ -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; * *

Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1 * making it easy to work together. + * + *

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 diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java deleted file mode 100644 index 0ca48f61bf..0000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java +++ /dev/null @@ -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. - * - *

If you change your main robot class, change the parameter type. - */ - public static void main(String... args) { - RobotBase.startRobot(Robot::new); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java deleted file mode 100644 index e758511a63..0000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java +++ /dev/null @@ -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. - * - *

Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1 - * making it easy to work together. - * - *

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()); - } -}