mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Cleaned up C++ examples (#672)
This commit is contained in:
committed by
Peter Johnson
parent
6401aa1fde
commit
45d48d6b5a
@@ -9,7 +9,7 @@
|
||||
|
||||
ExampleCommand::ExampleCommand() {
|
||||
// Use Requires() here to declare subsystem dependencies
|
||||
// eg. Requires(Robot::chassis.get());
|
||||
// eg. Requires(&Robot::chassis);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
|
||||
@@ -0,0 +1,31 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017 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 "MyAutoCommand.h"
|
||||
|
||||
MyAutoCommand::MyAutoCommand() {
|
||||
// Use Requires() here to declare subsystem dependencies
|
||||
// eg. Requires(&Robot::chassis);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void MyAutoCommand::Initialize() {}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
void MyAutoCommand::Execute() {}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool MyAutoCommand::IsFinished() {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void MyAutoCommand::End() {}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
void MyAutoCommand::Interrupted() {}
|
||||
@@ -0,0 +1,20 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017 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 <Commands/Command.h>
|
||||
|
||||
class MyAutoCommand : public frc::Command {
|
||||
public:
|
||||
MyAutoCommand();
|
||||
void Initialize() override;
|
||||
void Execute() override;
|
||||
bool IsFinished() override;
|
||||
void End() override;
|
||||
void Interrupted() override;
|
||||
};
|
||||
@@ -5,8 +5,6 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <Commands/Command.h>
|
||||
#include <Commands/Scheduler.h>
|
||||
#include <IterativeRobot.h>
|
||||
@@ -15,15 +13,14 @@
|
||||
#include <SmartDashboard/SmartDashboard.h>
|
||||
|
||||
#include "Commands/ExampleCommand.h"
|
||||
#include "Commands/MyAutoCommand.h"
|
||||
|
||||
class Robot : public frc::IterativeRobot {
|
||||
public:
|
||||
void RobotInit() override {
|
||||
defaultAuto.reset(new ExampleCommand());
|
||||
chooser.AddDefault("Default Auto", defaultAuto.get());
|
||||
// myAuto.reset(new MyAutoCommand());
|
||||
// chooser.AddObject("My Auto", myAuto.get());
|
||||
frc::SmartDashboard::PutData("Auto Modes", &chooser);
|
||||
m_chooser.AddDefault("Default Auto", &m_defaultAuto);
|
||||
m_chooser.AddObject("My Auto", &m_myAuto);
|
||||
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -54,19 +51,18 @@ public:
|
||||
* to the if-else structure below with additional strings & commands.
|
||||
*/
|
||||
void AutonomousInit() override {
|
||||
/* std::string autoSelected =
|
||||
frc::SmartDashboard::GetString("Auto Selector", "Default");
|
||||
std::string autoSelected = frc::SmartDashboard::GetString(
|
||||
"Auto Selector", "Default");
|
||||
if (autoSelected == "My Auto") {
|
||||
autonomousCommand.reset(new MyAutoCommand());
|
||||
m_autonomousCommand = &m_myAuto;
|
||||
} else {
|
||||
m_autonomousCommand = &m_defaultAuto;
|
||||
}
|
||||
else {
|
||||
autonomousCommand.reset(new ExampleCommand());
|
||||
} */
|
||||
|
||||
autonomousCommand = chooser.GetSelected();
|
||||
m_autonomousCommand = m_chooser.GetSelected();
|
||||
|
||||
if (autonomousCommand != nullptr) {
|
||||
autonomousCommand->Start();
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Start();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -79,9 +75,9 @@ public:
|
||||
// teleop starts running. If you want the autonomous to
|
||||
// continue until interrupted by another command, remove
|
||||
// this line or comment it out.
|
||||
if (autonomousCommand != nullptr) {
|
||||
autonomousCommand->Cancel();
|
||||
autonomousCommand = nullptr;
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Cancel();
|
||||
m_autonomousCommand = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -92,10 +88,10 @@ public:
|
||||
private:
|
||||
// Have it null by default so that if testing teleop it
|
||||
// doesn't have undefined behavior and potentially crash.
|
||||
frc::Command* autonomousCommand = nullptr;
|
||||
std::unique_ptr<frc::Command> defaultAuto;
|
||||
// std::unique_ptr<frc::Command> myAuto;
|
||||
frc::SendableChooser<frc::Command*> chooser;
|
||||
frc::Command* m_autonomousCommand = nullptr;
|
||||
ExampleCommand m_defaultAuto;
|
||||
MyAutoCommand m_myAuto;
|
||||
frc::SendableChooser<frc::Command*> m_chooser;
|
||||
};
|
||||
|
||||
START_ROBOT_CLASS(Robot)
|
||||
|
||||
@@ -16,10 +16,10 @@
|
||||
|
||||
// For example to map the left and right motors, you could define the
|
||||
// following variables to use with your drivetrain subsystem.
|
||||
// constexpr int LEFTMOTOR = 1;
|
||||
// constexpr int RIGHTMOTOR = 2;
|
||||
// constexpr int kLeftMotor = 1;
|
||||
// constexpr int kRightMotor = 2;
|
||||
|
||||
// If you are using multiple modules, make sure to define both the port
|
||||
// number and the module. For example you with a rangefinder:
|
||||
// constexpr int RANGE_FINDER_PORT = 1;
|
||||
// constexpr int RANGE_FINDER_MODULE = 1;
|
||||
// constexpr int kRangeFinderPort = 1;
|
||||
// constexpr int kRangeFinderModule = 1;
|
||||
|
||||
Reference in New Issue
Block a user