Remove SampleRobot (#1658)

SampleRobot provides no benefits over RobotBase to advanced teams and
TimedRobot is recommended for everyone else.

A skeleton template for RobotBase was added.
This commit is contained in:
Tyler Veness
2019-07-15 18:09:47 -07:00
committed by Peter Johnson
parent 62be0392b6
commit 73ec940786
13 changed files with 188 additions and 679 deletions

View File

@@ -1,86 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "frc/SampleRobot.h"
#include <hal/DriverStation.h>
#include <hal/FRCUsageReporting.h>
#include <hal/HALBase.h>
#include <networktables/NetworkTable.h>
#include <wpi/raw_ostream.h>
#include "frc/DriverStation.h"
#include "frc/Timer.h"
#include "frc/livewindow/LiveWindow.h"
using namespace frc;
void SampleRobot::StartCompetition() {
LiveWindow* lw = LiveWindow::GetInstance();
RobotInit();
// Tell the DS that the robot is ready to be enabled
HAL_ObserveUserProgramStarting();
RobotMain();
if (!m_robotMainOverridden) {
while (true) {
if (IsDisabled()) {
m_ds.InDisabled(true);
Disabled();
m_ds.InDisabled(false);
while (IsDisabled()) m_ds.WaitForData();
} else if (IsAutonomous()) {
m_ds.InAutonomous(true);
Autonomous();
m_ds.InAutonomous(false);
while (IsAutonomous() && IsEnabled()) m_ds.WaitForData();
} else if (IsTest()) {
lw->SetEnabled(true);
m_ds.InTest(true);
Test();
m_ds.InTest(false);
while (IsTest() && IsEnabled()) m_ds.WaitForData();
lw->SetEnabled(false);
} else {
m_ds.InOperatorControl(true);
OperatorControl();
m_ds.InOperatorControl(false);
while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData();
}
}
}
}
void SampleRobot::RobotInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Disabled() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Autonomous() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::OperatorControl() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Test() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
SampleRobot::SampleRobot() {
HAL_Report(HALUsageReporting::kResourceType_Framework,
HALUsageReporting::kFramework_Simple);
}

View File

@@ -1,109 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <wpi/deprecated.h>
#include "frc/RobotBase.h"
namespace frc {
class SampleRobot : public RobotBase {
public:
/**
* Start a competition.
*
* This code needs to track the order of the field starting to ensure that
* everything happens in the right order. Repeatedly run the correct method,
* either Autonomous or OperatorControl or Test when the robot is enabled.
* After running the correct method, wait for some state to change, either the
* other mode starts or the robot is disabled. Then go back and wait for the
* robot to be enabled again.
*/
void StartCompetition() override;
/**
* Robot-wide initialization code should go here.
*
* Users should override this method for default Robot-wide initialization
* which will be called when the robot is first powered on. It will be called
* exactly one time.
*
* Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
* indicators will be off until RobotInit() exits. Code in RobotInit() that
* waits for enable will cause the robot to never indicate that the code is
* ready, causing the robot to be bypassed in a match.
*/
virtual void RobotInit();
/**
* Disabled should go here.
*
* Programmers should override this method to run code that should run while
* the field is disabled.
*/
virtual void Disabled();
/**
* Autonomous should go here.
*
* Programmers should override this method to run code that should run while
* the field is in the autonomous period. This will be called once each time
* the robot enters the autonomous state.
*/
virtual void Autonomous();
/**
* Operator control (tele-operated) code should go here.
*
* Programmers should override this method to run code that should run while
* the field is in the Operator Control (tele-operated) period. This is called
* once each time the robot enters the teleop state.
*/
virtual void OperatorControl();
/**
* Test program should go here.
*
* Programmers should override this method to run code that executes while the
* robot is in test mode. This will be called once whenever the robot enters
* test mode
*/
virtual void Test();
/**
* Robot main program for free-form programs.
*
* This should be overridden by user subclasses if the intent is to not use
* the Autonomous() and OperatorControl() methods. In that case, the program
* is responsible for sensing when to run the autonomous and operator control
* functions in their program.
*
* This method will be called immediately after the constructor is called. If
* it has not been overridden by a user subclass (i.e. the default version
* runs), then the Autonomous() and OperatorControl() methods will be called.
*/
virtual void RobotMain();
protected:
WPI_DEPRECATED(
"WARNING: While it may look like a good choice to use for your code if "
"you're inexperienced, don't. Unless you know what you are doing, "
"complex code will be much more difficult under this system. Use "
"TimedRobot or Command-Based instead.")
SampleRobot();
virtual ~SampleRobot() = default;
SampleRobot(SampleRobot&&) = default;
SampleRobot& operator=(SampleRobot&&) = default;
private:
bool m_robotMainOverridden = true;
};
} // namespace frc

View File

@@ -56,7 +56,6 @@
#include "frc/RobotDrive.h"
#include "frc/SD540.h"
#include "frc/SPI.h"
#include "frc/SampleRobot.h"
#include "frc/SensorUtil.h"
#include "frc/SerialPort.h"
#include "frc/Servo.h"

View File

@@ -0,0 +1,66 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <hal/DriverStation.h>
#include <frc/DriverStation.h>
#include <frc/livewindow/LiveWindow.h>
#include <frc/shuffleboard/Shuffleboard.h>
#include <networktables/NetworkTable.h>
void Robot::RobotInit() {}
void Robot::Disabled() {}
void Robot::Autonomous() {}
void Robot::Teleop() {}
void Robot::Test() {}
void Robot::StartCompetition() {
auto& lw = *frc::LiveWindow::GetInstance();
RobotInit();
// Tell the DS that the robot is ready to be enabled
HAL_ObserveUserProgramStarting();
while (true) {
if (IsDisabled()) {
m_ds.InDisabled(true);
Disabled();
m_ds.InDisabled(false);
while (IsDisabled()) m_ds.WaitForData();
} else if (IsAutonomous()) {
m_ds.InAutonomous(true);
Autonomous();
m_ds.InAutonomous(false);
while (IsAutonomous() && IsEnabled()) m_ds.WaitForData();
} else if (IsTest()) {
lw.SetEnabled(true);
frc::Shuffleboard::EnableActuatorWidgets();
m_ds.InTest(true);
Test();
m_ds.InTest(false);
while (IsTest() && IsEnabled()) m_ds.WaitForData();
lw.SetEnabled(false);
frc::Shuffleboard::DisableActuatorWidgets();
} else {
m_ds.InOperatorControl(true);
Teleop();
m_ds.InOperatorControl(false);
while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData();
}
}
}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,21 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/RobotBase.h>
class Robot : public frc::RobotBase {
public:
void RobotInit();
void Disabled();
void Autonomous();
void Teleop();
void Test();
void StartCompetition() override;
};

View File

@@ -1,92 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <iostream>
#include <frc/Timer.h>
#include <frc/smartdashboard/SmartDashboard.h>
Robot::Robot() {
// Note SmartDashboard is not initialized here, wait until RobotInit() to make
// SmartDashboard calls
m_robotDrive.SetExpiration(0.1);
}
void Robot::RobotInit() {
m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
/**
* This autonomous (along with the chooser code above) shows how to select
* between different autonomous modes using the dashboard. The sendable chooser
* code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
* remove all of the chooser code and uncomment the GetString line to get the
* auto name from the text box below the Gyro.
*
* You can add additional auto modes by adding additional comparisons to the
* if-else structure below with additional strings. If using the SendableChooser
* make sure to add them to the chooser code above as well.
*/
void Robot::Autonomous() {
std::string autoSelected = m_chooser.GetSelected();
// std::string autoSelected = frc::SmartDashboard::GetString(
// "Auto Selector", kAutoNameDefault);
std::cout << "Auto selected: " << autoSelected << std::endl;
// MotorSafety improves safety when motors are updated in loops but is
// disabled here because motor updates are not looped in this autonomous mode.
m_robotDrive.SetSafetyEnabled(false);
if (autoSelected == kAutoNameCustom) {
// Custom Auto goes here
std::cout << "Running custom Autonomous" << std::endl;
// Spin at half speed for two seconds
m_robotDrive.ArcadeDrive(0.0, 0.5);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
} else {
// Default Auto goes here
std::cout << "Running default Autonomous" << std::endl;
// Drive forwards at half speed for two seconds
m_robotDrive.ArcadeDrive(-0.5, 0.0);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
}
}
/**
* Runs the motors with arcade steering.
*/
void Robot::OperatorControl() {
m_robotDrive.SetSafetyEnabled(true);
while (IsOperatorControl() && IsEnabled()) {
// Drive with arcade style (use right stick)
m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
// The motors will be updated every 5ms
frc::Wait(0.005);
}
}
/**
* Runs during test mode
*/
void Robot::Test() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -1,49 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <string>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SampleRobot.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/smartdashboard/SendableChooser.h>
/**
* This is a demo program showing the use of the DifferentialDrive class. The
* SampleRobot class is the base of a robot application that will automatically
* call your Autonomous and OperatorControl methods at the right time as
* controlled by the switches on the driver station or the field controls.
*
* WARNING: While it may look like a good choice to use for your code if you're
* inexperienced, don't. Unless you know what you are doing, complex code will
* be much more difficult under this system. Use TimedRobot or Command-Based
* instead if you're new.
*/
class Robot : public frc::SampleRobot {
public:
Robot();
void RobotInit() override;
void Autonomous() override;
void OperatorControl() override;
void Test() override;
private:
// Robot drive system
frc::PWMVictorSPX m_leftMotor{0};
frc::PWMVictorSPX m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::Joystick m_stick{0};
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
};

View File

@@ -26,6 +26,15 @@
"foldername": "timedskeleton",
"gradlebase": "cpp"
},
{
"name": "RobotBase Skeleton (Advanced)",
"description": "Skeleton (stub) code for RobotBase",
"tags": [
"RobotBase", "Skeleton"
],
"foldername": "robotbaseskeleton",
"gradlebase": "cpp"
},
{
"name": "Command Robot",
"description": "Command style",
@@ -34,14 +43,5 @@
],
"foldername": "commandbased",
"gradlebase": "cpp"
},
{
"name": "Sample Robot",
"description": "Sample style",
"tags": [
"Sample"
],
"foldername": "sample",
"gradlebase": "cpp"
}
]

View File

@@ -1,166 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj;
import edu.wpi.first.hal.FRCNetComm.tInstances;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
/**
* A simple robot base class that knows the standard FRC competition states (disabled, autonomous,
* or operator controlled).
*
* <p>You can build a simple robot program off of this by overriding the robotinit(), disabled(),
* autonomous() and operatorControl() methods. The startCompetition() method will calls these
* methods (sometimes repeatedly). depending on the state of the competition.
*
* <p>Alternatively you can override the robotMain() method and manage all aspects of the robot
* yourself.
*
* @deprecated WARNING: While it may look like a good choice to use for your code if you're
* inexperienced, don't. Unless you know what you are doing, complex code will
* be much more difficult under this system. Use TimedRobot or Command-Based
* instead.
*/
@Deprecated
public class SampleRobot extends RobotBase {
private boolean m_robotMainOverridden = true;
/**
* Create a new SampleRobot.
*/
public SampleRobot() {
HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Simple);
}
/**
* Robot-wide initialization code should go here.
*
* <p>Users should override this method for default Robot-wide initialization which will be called
* when the robot is first powered on. It will be called exactly one time.
*
* <p>Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off
* until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to
* never indicate that the code is ready, causing the robot to be bypassed in a match.
*/
protected void robotInit() {
System.out.println("Default robotInit() method running, consider providing your own");
}
/**
* Disabled should go here. Users should override this method to run code that should run while
* the field is disabled.
*
* <p>Called once each time the robot enters the disabled state.
*/
protected void disabled() {
System.out.println("Default disabled() method running, consider providing your own");
}
/**
* Autonomous should go here. Users should add autonomous code to this method that should run
* while the field is in the autonomous period.
*
* <p>Called once each time the robot enters the autonomous state.
*/
public void autonomous() {
System.out.println("Default autonomous() method running, consider providing your own");
}
/**
* Operator control (tele-operated) code should go here. Users should add Operator Control code to
* this method that should run while the field is in the Operator Control (tele-operated) period.
*
* <p>Called once each time the robot enters the operator-controlled state.
*/
public void operatorControl() {
System.out.println("Default operatorControl() method running, consider providing your own");
}
/**
* Test code should go here. Users should add test code to this method that should run while the
* robot is in test mode.
*/
@SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void test() {
System.out.println("Default test() method running, consider providing your own");
}
/**
* Robot main program for free-form programs.
*
* <p>This should be overridden by user subclasses if the intent is to not use the autonomous()
* and operatorControl() methods. In that case, the program is responsible for sensing when to run
* the autonomous and operator control functions in their program.
*
* <p>This method will be called immediately after the constructor is called. If it has not been
* overridden by a user subclass (i.e. the default version runs), then the robotInit(),
* disabled(), autonomous() and operatorControl() methods will be called.
*/
public void robotMain() {
m_robotMainOverridden = false;
}
/**
* Start a competition. This code tracks the order of the field starting to ensure that everything
* happens in the right order. Repeatedly run the correct method, either Autonomous or
* OperatorControl when the robot is enabled. After running the correct method, wait for some
* state to change, either the other mode starts or the robot is disabled. Then go back and wait
* for the robot to be enabled again.
*/
@SuppressWarnings("PMD.CyclomaticComplexity")
@Override
public void startCompetition() {
robotInit();
// Tell the DS that the robot is ready to be enabled
HAL.observeUserProgramStarting();
robotMain();
if (!m_robotMainOverridden) {
while (true) {
if (isDisabled()) {
m_ds.InDisabled(true);
disabled();
m_ds.InDisabled(false);
while (isDisabled()) {
Timer.delay(0.01);
}
} else if (isAutonomous()) {
m_ds.InAutonomous(true);
autonomous();
m_ds.InAutonomous(false);
while (isAutonomous() && !isDisabled()) {
Timer.delay(0.01);
}
} else if (isTest()) {
LiveWindow.setEnabled(true);
Shuffleboard.enableActuatorWidgets();
m_ds.InTest(true);
test();
m_ds.InTest(false);
while (isTest() && isEnabled()) {
Timer.delay(0.01);
}
LiveWindow.setEnabled(false);
Shuffleboard.disableActuatorWidgets();
} else {
m_ds.InOperatorControl(true);
operatorControl();
m_ds.InOperatorControl(false);
while (isOperatorControl() && !isDisabled()) {
Timer.delay(0.01);
}
}
} /* while loop */
}
}
}

View File

@@ -1,11 +1,11 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.templates.sample;
package edu.wpi.first.wpilibj.templates.robotbaseskeleton;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -0,0 +1,80 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.templates.robotbaseskeleton;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
/**
* The VM is configured to automatically run this class. If you change the name
* of this class or the package after creating this project, you must also
* update the build.gradle file in the project.
*/
public class Robot extends RobotBase {
public void robotInit() {
}
public void disabled() {
}
public void autonomous() {
}
public void teleop() {
}
public void test() {
}
@SuppressWarnings("PMD.CyclomaticComplexity")
@Override
public void startCompetition() {
robotInit();
// Tell the DS that the robot is ready to be enabled
HAL.observeUserProgramStarting();
while (true) {
if (isDisabled()) {
m_ds.InDisabled(true);
disabled();
m_ds.InDisabled(false);
while (isDisabled()) {
m_ds.waitForData();
}
} else if (isAutonomous()) {
m_ds.InAutonomous(true);
autonomous();
m_ds.InAutonomous(false);
while (isAutonomous() && !isDisabled()) {
m_ds.waitForData();
}
} else if (isTest()) {
LiveWindow.setEnabled(true);
Shuffleboard.enableActuatorWidgets();
m_ds.InTest(true);
test();
m_ds.InTest(false);
while (isTest() && isEnabled()) {
m_ds.waitForData();
}
LiveWindow.setEnabled(false);
Shuffleboard.disableActuatorWidgets();
} else {
m_ds.InOperatorControl(true);
teleop();
m_ds.InOperatorControl(false);
while (isOperatorControl() && !isDisabled()) {
m_ds.waitForData();
}
}
}
}
}

View File

@@ -1,155 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.templates.sample;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.wpilibj.SampleRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* This is a demo program showing the use of the RobotDrive class. The
* SampleRobot class is the base of a robot application that will automatically
* call your Autonomous and OperatorControl methods at the right time as
* controlled by the switches on the driver station or the field controls.
*
* <p>The VM is configured to automatically run this class, and to call the
* functions corresponding to each mode, as described in the SampleRobot
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the build.properties file in the
* project.
*
* <p>WARNING: While it may look like a good choice to use for your code if
* you're inexperienced, don't. Unless you know what you are doing, complex code
* will be much more difficult under this system. Use TimedRobot or
* Command-Based instead if you're new.
*/
public class Robot extends SampleRobot {
private static final String kDefaultAuto = "Default";
private static final String kCustomAuto = "My Auto";
private final DifferentialDrive m_robotDrive
= new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
private final Joystick m_stick = new Joystick(0);
private final SendableChooser<String> m_chooser = new SendableChooser<>();
public Robot() {
m_robotDrive.setExpiration(0.1);
}
@Override
public void robotInit() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto modes", m_chooser);
}
/**
* This autonomous (along with the chooser code above) shows how to select
* between different autonomous modes using the dashboard. The sendable
* chooser code works with the Java SmartDashboard. If you prefer the
* LabVIEW Dashboard, remove all of the chooser code and uncomment the
* getString line to get the auto name from the text box below the Gyro
*
* <p>You can add additional auto modes by adding additional comparisons to
* the if-else structure below with additional strings. If using the
* SendableChooser make sure to add them to the chooser code above as well.
*
* <p>If you wanted to run a similar autonomous mode with an TimedRobot
* you would write:
*
* <blockquote><pre>{@code
* Timer timer = new Timer();
*
* // This function is run once each time the robot enters autonomous mode
* public void autonomousInit() {
* timer.reset();
* timer.start();
* }
*
* // This function is called periodically during autonomous
* public void autonomousPeriodic() {
* // Drive for 2 seconds
* if (timer.get() < 2.0) {
* myRobot.drive(-0.5, 0.0); // drive forwards half speed
* } else if (timer.get() < 5.0) {
* myRobot.drive(-1.0, 0.0); // drive forwards full speed
* } else {
* myRobot.drive(0.0, 0.0); // stop robot
* }
* }
* }</pre></blockquote>
*/
@Override
public void autonomous() {
String autoSelected = m_chooser.getSelected();
// String autoSelected = SmartDashboard.getString("Auto Selector",
// defaultAuto);
System.out.println("Auto selected: " + autoSelected);
// MotorSafety improves safety when motors are updated in loops
// but is disabled here because motor updates are not looped in
// this autonomous mode.
m_robotDrive.setSafetyEnabled(false);
switch (autoSelected) {
case kCustomAuto:
// Spin at half speed for two seconds
m_robotDrive.arcadeDrive(0.0, 0.5);
Timer.delay(2.0);
// Stop robot
m_robotDrive.arcadeDrive(0.0, 0.0);
break;
case kDefaultAuto:
default:
// Drive forwards for two seconds
m_robotDrive.arcadeDrive(-0.5, 0.0);
Timer.delay(2.0);
// Stop robot
m_robotDrive.arcadeDrive(0.0, 0.0);
break;
}
}
/**
* Runs the motors with arcade steering.
*
* <p>If you wanted to run a similar teleoperated mode with an TimedRobot
* you would write:
*
* <blockquote><pre>{@code
* // This function is called periodically during operator control
* public void teleopPeriodic() {
* myRobot.arcadeDrive(stick);
* }
* }</pre></blockquote>
*/
@Override
public void operatorControl() {
m_robotDrive.setSafetyEnabled(true);
while (isOperatorControl() && isEnabled()) {
// Drive arcade style
m_robotDrive.arcadeDrive(-m_stick.getY(), m_stick.getX());
// The motors will be updated every 5ms
Timer.delay(0.005);
}
}
/**
* Runs during test mode.
*/
@Override
public void test() {
}
}

View File

@@ -29,6 +29,16 @@
"gradlebase": "java",
"mainclass": "Main"
},
{
"name": "RobotBase Skeleton (Advanced)",
"description": "Skeleton (stub) code for RobotBase",
"tags": [
"RobotBase", "Skeleton"
],
"foldername": "robotbaseskeleton",
"gradlebase": "java",
"mainclass": "Main"
},
{
"name": "Command Robot",
"description": "Command style",
@@ -38,15 +48,5 @@
"foldername": "commandbased",
"gradlebase": "java",
"mainclass": "Main"
},
{
"name": "Sample Robot",
"description": "Sample style",
"tags": [
"Sample"
],
"foldername": "sample",
"gradlebase": "java",
"mainclass": "Main"
}
]