mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[examples] Hatchbots: Add telemetry (#5011)
This commit is contained in:
@@ -62,7 +62,7 @@ def tagList = [
|
||||
"Swerve Drive",
|
||||
|
||||
/* --- Telemetry --- */
|
||||
"SmartDashboard", "Shuffleboard", "Sendable",
|
||||
"SmartDashboard", "Shuffleboard", "Sendable", "DataLog",
|
||||
|
||||
/* --- Controls --- */
|
||||
"PID", "State-Space", "Ramsete", "Path Following", "Trajectory", "SysId",
|
||||
|
||||
@@ -4,10 +4,19 @@
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <frc/DataLogManager.h>
|
||||
#include <frc/DriverStation.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <frc2/command/CommandScheduler.h>
|
||||
|
||||
void Robot::RobotInit() {}
|
||||
void Robot::RobotInit() {
|
||||
// Start recording to data log
|
||||
frc::DataLogManager::Start();
|
||||
|
||||
// Record DS control and joystick data.
|
||||
// Change to `false` to not record joystick data.
|
||||
frc::DriverStation::StartDataLog(frc::DataLogManager::GetLog(), true);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called every 20 ms, no matter the mode. Use
|
||||
|
||||
@@ -16,6 +16,35 @@ RobotContainer::RobotContainer() {
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
|
||||
// Put subsystems to dashboard.
|
||||
frc::Shuffleboard::GetTab("Drivetrain").Add(m_drive);
|
||||
frc::Shuffleboard::GetTab("HatchSubsystem").Add(m_hatch);
|
||||
|
||||
// Log Shuffleboard events for command initialize, execute, finish, interrupt
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInitialize(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command initialized", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandExecute(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command executed", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandFinish(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command finished", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInterrupt(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command interrupted", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
|
||||
// Configure the button bindings
|
||||
ConfigureButtonBindings();
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#include "subsystems/DriveSubsystem.h"
|
||||
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
using namespace DriveConstants;
|
||||
|
||||
DriveSubsystem::DriveSubsystem()
|
||||
@@ -40,14 +42,17 @@ double DriveSubsystem::GetAverageEncoderDistance() {
|
||||
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetLeftEncoder() {
|
||||
return m_leftEncoder;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetRightEncoder() {
|
||||
return m_rightEncoder;
|
||||
}
|
||||
|
||||
void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
m_drive.SetMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.AddDoubleProperty(
|
||||
"leftDistance", [this] { return m_leftEncoder.GetDistance(); }, nullptr);
|
||||
builder.AddDoubleProperty(
|
||||
"rightDistance", [this] { return m_rightEncoder.GetDistance(); },
|
||||
nullptr);
|
||||
}
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#include "subsystems/HatchSubsystem.h"
|
||||
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
using namespace HatchConstants;
|
||||
|
||||
HatchSubsystem::HatchSubsystem()
|
||||
@@ -21,3 +23,13 @@ frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
|
||||
return this->RunOnce(
|
||||
[this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse); });
|
||||
}
|
||||
|
||||
void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.AddBooleanProperty(
|
||||
"extended",
|
||||
[this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
|
||||
nullptr);
|
||||
}
|
||||
|
||||
@@ -43,20 +43,6 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
double GetAverageEncoderDistance();
|
||||
|
||||
/**
|
||||
* Gets the left drive encoder.
|
||||
*
|
||||
* @return the left drive encoder
|
||||
*/
|
||||
frc::Encoder& GetLeftEncoder();
|
||||
|
||||
/**
|
||||
* Gets the right drive encoder.
|
||||
*
|
||||
* @return the right drive encoder
|
||||
*/
|
||||
frc::Encoder& GetRightEncoder();
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive
|
||||
* more slowly.
|
||||
@@ -65,6 +51,8 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
void SetMaxOutput(double maxOutput);
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
// Components (e.g. motor controllers and sensors) should generally be
|
||||
// declared private and exposed only through public methods.
|
||||
|
||||
@@ -27,6 +27,8 @@ class HatchSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
frc2::CommandPtr ReleaseHatchCommand();
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
// Components (e.g. motor controllers and sensors) should generally be
|
||||
// declared private and exposed only through public methods.
|
||||
|
||||
@@ -4,10 +4,19 @@
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <frc/DataLogManager.h>
|
||||
#include <frc/DriverStation.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <frc2/command/CommandScheduler.h>
|
||||
|
||||
void Robot::RobotInit() {}
|
||||
void Robot::RobotInit() {
|
||||
// Start recording to data log
|
||||
frc::DataLogManager::Start();
|
||||
|
||||
// Record DS control and joystick data.
|
||||
// Change to `false` to not record joystick data.
|
||||
frc::DriverStation::StartDataLog(frc::DataLogManager::GetLog(), true);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called every 20 ms, no matter the mode. Use
|
||||
|
||||
@@ -21,6 +21,35 @@ RobotContainer::RobotContainer() {
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
|
||||
// Put subsystems to dashboard.
|
||||
frc::Shuffleboard::GetTab("Drivetrain").Add(m_drive);
|
||||
frc::Shuffleboard::GetTab("HatchSubsystem").Add(m_hatch);
|
||||
|
||||
// Log Shuffleboard events for command initialize, execute, finish, interrupt
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInitialize(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command initialized", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandExecute(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command executed", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandFinish(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command finished", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInterrupt(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command interrupted", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
|
||||
// Configure the button bindings
|
||||
ConfigureButtonBindings();
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#include "subsystems/DriveSubsystem.h"
|
||||
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
using namespace DriveConstants;
|
||||
|
||||
DriveSubsystem::DriveSubsystem()
|
||||
@@ -40,14 +42,17 @@ double DriveSubsystem::GetAverageEncoderDistance() {
|
||||
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetLeftEncoder() {
|
||||
return m_leftEncoder;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetRightEncoder() {
|
||||
return m_rightEncoder;
|
||||
}
|
||||
|
||||
void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
m_drive.SetMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.AddDoubleProperty(
|
||||
"leftDistance", [this] { return m_leftEncoder.GetDistance(); }, nullptr);
|
||||
builder.AddDoubleProperty(
|
||||
"rightDistance", [this] { return m_rightEncoder.GetDistance(); },
|
||||
nullptr);
|
||||
}
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#include "subsystems/HatchSubsystem.h"
|
||||
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
using namespace HatchConstants;
|
||||
|
||||
HatchSubsystem::HatchSubsystem()
|
||||
@@ -17,3 +19,13 @@ void HatchSubsystem::GrabHatch() {
|
||||
void HatchSubsystem::ReleaseHatch() {
|
||||
m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
|
||||
}
|
||||
|
||||
void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.AddBooleanProperty(
|
||||
"extended",
|
||||
[this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
|
||||
nullptr);
|
||||
}
|
||||
|
||||
@@ -43,20 +43,6 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
double GetAverageEncoderDistance();
|
||||
|
||||
/**
|
||||
* Gets the left drive encoder.
|
||||
*
|
||||
* @return the left drive encoder
|
||||
*/
|
||||
frc::Encoder& GetLeftEncoder();
|
||||
|
||||
/**
|
||||
* Gets the right drive encoder.
|
||||
*
|
||||
* @return the right drive encoder
|
||||
*/
|
||||
frc::Encoder& GetRightEncoder();
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive
|
||||
* more slowly.
|
||||
@@ -65,6 +51,8 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
void SetMaxOutput(double maxOutput);
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
// Components (e.g. motor controllers and sensors) should generally be
|
||||
// declared private and exposed only through public methods.
|
||||
|
||||
@@ -26,6 +26,8 @@ class HatchSubsystem : public frc2::SubsystemBase {
|
||||
*/
|
||||
void ReleaseHatch();
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
// Components (e.g. motor controllers and sensors) should generally be
|
||||
// declared private and exposed only through public methods.
|
||||
|
||||
@@ -1,72 +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 "Robot.h"
|
||||
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <frc2/command/CommandScheduler.h>
|
||||
|
||||
void Robot::RobotInit() {}
|
||||
|
||||
/**
|
||||
* This function is called every 20 ms, no matter the mode. Use
|
||||
* this for items like diagnostics that you want to run during disabled,
|
||||
* autonomous, teleoperated and test.
|
||||
*
|
||||
* <p> This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
*/
|
||||
void Robot::RobotPeriodic() {
|
||||
frc2::CommandScheduler::GetInstance().Run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode. You
|
||||
* can use it to reset any subsystem information you want to clear when the
|
||||
* robot is disabled.
|
||||
*/
|
||||
void Robot::DisabledInit() {}
|
||||
|
||||
void Robot::DisabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link
|
||||
* RobotContainer} class.
|
||||
*/
|
||||
void Robot::AutonomousInit() {
|
||||
m_autonomousCommand = m_container.GetAutonomousCommand();
|
||||
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Schedule();
|
||||
}
|
||||
}
|
||||
|
||||
void Robot::AutonomousPeriodic() {}
|
||||
|
||||
void Robot::TeleopInit() {
|
||||
// This makes sure that the autonomous stops running when
|
||||
// teleop starts running. If you want the autonomous to
|
||||
// continue until interrupted by another command, remove
|
||||
// this line or comment it out.
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Cancel();
|
||||
m_autonomousCommand = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
void Robot::TeleopPeriodic() {}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
void Robot::TestPeriodic() {}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,62 +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 "RobotContainer.h"
|
||||
|
||||
#include <frc/shuffleboard/Shuffleboard.h>
|
||||
#include <frc2/command/CommandScheduler.h>
|
||||
#include <frc2/command/button/JoystickButton.h>
|
||||
|
||||
RobotContainer::RobotContainer() {
|
||||
// Initialize all of your commands and subsystems here
|
||||
|
||||
// Set names of commands
|
||||
m_instantCommand1.SetName("Instant Command 1");
|
||||
m_instantCommand2.SetName("Instant Command 2");
|
||||
m_waitCommand.SetName("Wait 5 Seconds Command");
|
||||
|
||||
// Set the scheduler to log Shuffleboard events for command initialize,
|
||||
// interrupt, finish
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInitialize(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command Initialized", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandInterrupt(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command Interrupted", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
frc2::CommandScheduler::GetInstance().OnCommandFinish(
|
||||
[](const frc2::Command& command) {
|
||||
frc::Shuffleboard::AddEventMarker(
|
||||
"Command Finished", command.GetName(),
|
||||
frc::ShuffleboardEventImportance::kNormal);
|
||||
});
|
||||
|
||||
// Configure the button bindings
|
||||
ConfigureButtonBindings();
|
||||
}
|
||||
|
||||
void RobotContainer::ConfigureButtonBindings() {
|
||||
// Configure your button bindings here
|
||||
|
||||
// Run instant command 1 when the 'A' button is pressed
|
||||
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
|
||||
.OnTrue(&m_instantCommand1);
|
||||
// Run instant command 2 when the 'X' button is pressed
|
||||
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
|
||||
.OnTrue(&m_instantCommand2);
|
||||
// Run instant command 3 when the 'Y' button is held; release early to
|
||||
// interrupt
|
||||
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
|
||||
.OnTrue(&m_waitCommand);
|
||||
}
|
||||
|
||||
frc2::Command* RobotContainer::GetAutonomousCommand() {
|
||||
// no auto
|
||||
return nullptr;
|
||||
}
|
||||
@@ -1,19 +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.
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* The Constants header provides a convenient place for teams to hold robot-wide
|
||||
* numerical or boolean constants. This should not be used for any other
|
||||
* purpose.
|
||||
*
|
||||
* It is generally a good idea to place constants into subsystem- or
|
||||
* command-specific namespaces within this header, which can then be used where
|
||||
* they are needed.
|
||||
*/
|
||||
|
||||
namespace OIConstants {
|
||||
constexpr int kDriverControllerPort = 0;
|
||||
} // namespace OIConstants
|
||||
@@ -1,30 +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.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc2/command/Command.h>
|
||||
|
||||
#include "RobotContainer.h"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void RobotInit() override;
|
||||
void RobotPeriodic() override;
|
||||
void DisabledInit() override;
|
||||
void DisabledPeriodic() override;
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
void TestPeriodic() override;
|
||||
|
||||
private:
|
||||
// Have it null by default so that if testing teleop it
|
||||
// doesn't have undefined behavior and potentially crash.
|
||||
frc2::Command* m_autonomousCommand = nullptr;
|
||||
|
||||
RobotContainer m_container;
|
||||
};
|
||||
@@ -1,39 +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.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc2/command/Command.h>
|
||||
#include <frc2/command/InstantCommand.h>
|
||||
#include <frc2/command/WaitCommand.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since
|
||||
* Command-based is a "declarative" paradigm, very little robot logic should
|
||||
* actually be handled in the {@link Robot} periodic methods (other than the
|
||||
* scheduler calls). Instead, the structure of the robot (including subsystems,
|
||||
* commands, and button mappings) should be declared here.
|
||||
*/
|
||||
class RobotContainer {
|
||||
public:
|
||||
RobotContainer();
|
||||
|
||||
frc2::Command* GetAutonomousCommand();
|
||||
|
||||
private:
|
||||
// The robot's subsystems and commands are defined here...
|
||||
|
||||
// The driver's controller
|
||||
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
|
||||
|
||||
// Three commands that do nothing; for demonstration purposes.
|
||||
frc2::InstantCommand m_instantCommand1;
|
||||
frc2::InstantCommand m_instantCommand2;
|
||||
frc2::WaitCommand m_waitCommand{5_s};
|
||||
|
||||
void ConfigureButtonBindings();
|
||||
};
|
||||
@@ -356,6 +356,9 @@
|
||||
"Command-based",
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"Pneumatics",
|
||||
"XboxController"
|
||||
],
|
||||
@@ -371,6 +374,9 @@
|
||||
"Command-based",
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"Pneumatics",
|
||||
"PS4Controller"
|
||||
],
|
||||
@@ -407,17 +413,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Scheduler Event Logging",
|
||||
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the new command framework",
|
||||
"tags": [
|
||||
"Command-based",
|
||||
"Shuffleboard"
|
||||
],
|
||||
"foldername": "SchedulerEventLogging",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Frisbeebot",
|
||||
"description": "An example robot project for a simple frisbee shooter for the 2013 FRC game, Ultimate Ascent, demonstrating use of PID functionality in the command framework",
|
||||
|
||||
@@ -349,6 +349,9 @@
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Pneumatics",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"XboxController"
|
||||
],
|
||||
"foldername": "hatchbottraditional",
|
||||
@@ -365,6 +368,9 @@
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Pneumatics",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"PS4Controller"
|
||||
],
|
||||
"foldername": "hatchbotinlined",
|
||||
@@ -403,18 +409,6 @@
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Scheduler Event Logging",
|
||||
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the new command framework",
|
||||
"tags": [
|
||||
"Command-based",
|
||||
"Shuffleboard"
|
||||
],
|
||||
"foldername": "schedulereventlogging",
|
||||
"gradlebase": "java",
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Frisbeebot",
|
||||
"description": "An example robot project for a simple frisbee shooter for the 2013 FRC game, Ultimate Ascent, demonstrating use of PID functionality in the command framework",
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.hatchbotinlined;
|
||||
|
||||
import edu.wpi.first.wpilibj.DataLogManager;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
@@ -28,6 +30,13 @@ public class Robot extends TimedRobot {
|
||||
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||||
// autonomous chooser on the dashboard.
|
||||
m_robotContainer = new RobotContainer();
|
||||
|
||||
// Start recording to data log
|
||||
DataLogManager.start();
|
||||
|
||||
// Record DS control and joystick data.
|
||||
// Change to `false` to not record joystick data.
|
||||
DriverStation.startDataLog(DataLogManager.getLog(), true);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -9,9 +9,11 @@ import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.Autos;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.EventImportance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
|
||||
|
||||
@@ -63,6 +65,27 @@ public class RobotContainer {
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
Shuffleboard.getTab("Autonomous").add(m_chooser);
|
||||
|
||||
// Put subsystems to dashboard.
|
||||
Shuffleboard.getTab("Drivetrain").add(m_robotDrive);
|
||||
Shuffleboard.getTab("HatchSubsystem").add(m_hatchSubsystem);
|
||||
|
||||
// Set the scheduler to log Shuffleboard events for command initialize, interrupt, finish
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInitialize(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command initialized", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInterrupt(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command interrupted", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandFinish(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command finished", command.getName(), EventImportance.kNormal));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems;
|
||||
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants;
|
||||
@@ -78,24 +79,6 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the left drive encoder.
|
||||
*
|
||||
* @return the left drive encoder
|
||||
*/
|
||||
public Encoder getLeftEncoder() {
|
||||
return m_leftEncoder;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the right drive encoder.
|
||||
*
|
||||
* @return the right drive encoder
|
||||
*/
|
||||
public Encoder getRightEncoder() {
|
||||
return m_rightEncoder;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
@@ -104,4 +87,12 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
public void setMaxOutput(double maxOutput) {
|
||||
m_drive.setMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
super.initSendable(builder);
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.addDoubleProperty("leftDistance", m_leftEncoder::getDistance, null);
|
||||
builder.addDoubleProperty("rightDistance", m_rightEncoder::getDistance, null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,6 +7,7 @@ package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems;
|
||||
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward;
|
||||
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;
|
||||
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
|
||||
@@ -32,4 +33,11 @@ public class HatchSubsystem extends SubsystemBase {
|
||||
// implicitly require `this`
|
||||
return this.runOnce(() -> m_hatchSolenoid.set(kReverse));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
super.initSendable(builder);
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional;
|
||||
|
||||
import edu.wpi.first.wpilibj.DataLogManager;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
@@ -28,6 +30,13 @@ public class Robot extends TimedRobot {
|
||||
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||||
// autonomous chooser on the dashboard.
|
||||
m_robotContainer = new RobotContainer();
|
||||
|
||||
// Start recording to data log
|
||||
DataLogManager.start();
|
||||
|
||||
// Record DS control and joystick data.
|
||||
// Change to `false` to not record joystick data.
|
||||
DriverStation.startDataLog(DataLogManager.getLog(), true);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -17,9 +17,11 @@ import edu.wpi.first.wpilibj.examples.hatchbottraditional.commands.HalveDriveSpe
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.commands.ReleaseHatch;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.HatchSubsystem;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.EventImportance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
/**
|
||||
@@ -70,6 +72,31 @@ public class RobotContainer {
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
Shuffleboard.getTab("Autonomous").add(m_chooser);
|
||||
// Put subsystems to dashboard.
|
||||
Shuffleboard.getTab("Drivetrain").add(m_robotDrive);
|
||||
Shuffleboard.getTab("HatchSubsystem").add(m_hatchSubsystem);
|
||||
|
||||
// Log Shuffleboard events for command initialize, execute, finish, interrupt
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInitialize(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command initialized", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandExecute(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command executed", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandFinish(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command finished", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInterrupt(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command interrupted", command.getName(), EventImportance.kNormal));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems;
|
||||
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants;
|
||||
@@ -78,24 +79,6 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the left drive encoder.
|
||||
*
|
||||
* @return the left drive encoder
|
||||
*/
|
||||
public Encoder getLeftEncoder() {
|
||||
return m_leftEncoder;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the right drive encoder.
|
||||
*
|
||||
* @return the right drive encoder
|
||||
*/
|
||||
public Encoder getRightEncoder() {
|
||||
return m_rightEncoder;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
@@ -104,4 +87,12 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
public void setMaxOutput(double maxOutput) {
|
||||
m_drive.setMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
super.initSendable(builder);
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.addDoubleProperty("leftDistance", m_leftEncoder::getDistance, null);
|
||||
builder.addDoubleProperty("rightDistance", m_rightEncoder::getDistance, null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,6 +7,7 @@ package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems;
|
||||
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward;
|
||||
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;
|
||||
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.HatchConstants;
|
||||
@@ -29,4 +30,11 @@ public class HatchSubsystem extends SubsystemBase {
|
||||
public void releaseHatch() {
|
||||
m_hatchSolenoid.set(kReverse);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
super.initSendable(builder);
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, 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.schedulereventlogging;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
*/
|
||||
public final class Constants {
|
||||
/**
|
||||
* Example of an inner class. One can "import static [...].Constants.OIConstants.*" to gain access
|
||||
* to the constants contained within without having to preface the names with the class, greatly
|
||||
* reducing the amount of text required.
|
||||
*/
|
||||
public static final class OIConstants {
|
||||
// Example: the port of the driver's controller
|
||||
public static final int kDriverControllerPort = 0;
|
||||
}
|
||||
}
|
||||
@@ -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.schedulereventlogging;
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -1,102 +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.schedulereventlogging;
|
||||
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
|
||||
/**
|
||||
* The VM is configured to automatically run this class, and to call the functions corresponding to
|
||||
* each mode, as described in the TimedRobot documentation. 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 TimedRobot {
|
||||
private Command m_autonomousCommand;
|
||||
|
||||
private RobotContainer m_robotContainer;
|
||||
|
||||
/**
|
||||
* This function is run when the robot is first started up and should be used for any
|
||||
* initialization code.
|
||||
*/
|
||||
@Override
|
||||
public void robotInit() {
|
||||
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||||
// autonomous chooser on the dashboard.
|
||||
m_robotContainer = new RobotContainer();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
|
||||
* that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
|
||||
// commands, running already-scheduled commands, removing finished or interrupted commands,
|
||||
// and running subsystem periodic() methods. This must be called from the robot's periodic
|
||||
// block in order for anything in the Command-based framework to work.
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
|
||||
/*
|
||||
* String autoSelected = SmartDashboard.getString("Auto Selector",
|
||||
* "Default"); switch(autoSelected) { case "My Auto": autonomousCommand
|
||||
* = new MyAutoCommand(); break; case "Default Auto": default:
|
||||
* autonomousCommand = new ExampleCommand(); break; }
|
||||
*/
|
||||
|
||||
// schedule the autonomous command (example)
|
||||
if (m_autonomousCommand != null) {
|
||||
m_autonomousCommand.schedule();
|
||||
}
|
||||
}
|
||||
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
// This makes sure that the autonomous stops running when
|
||||
// teleop starts running. If you want the autonomous to
|
||||
// continue until interrupted by another command, remove
|
||||
// this line or comment it out.
|
||||
if (m_autonomousCommand != null) {
|
||||
m_autonomousCommand.cancel();
|
||||
}
|
||||
}
|
||||
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
// Cancels all running commands at the start of test mode.
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
@@ -1,88 +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.schedulereventlogging;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.schedulereventlogging.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.EventImportance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.WaitCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The driver's controller
|
||||
private final XboxController m_driverController =
|
||||
new XboxController(OIConstants.kDriverControllerPort);
|
||||
|
||||
// A few commands that do nothing, but will demonstrate the scheduler functionality
|
||||
private final CommandBase m_instantCommand1 = new InstantCommand();
|
||||
private final CommandBase m_instantCommand2 = new InstantCommand();
|
||||
private final CommandBase m_waitCommand = new WaitCommand(5);
|
||||
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Set names of commands
|
||||
m_instantCommand1.setName("Instant Command 1");
|
||||
m_instantCommand2.setName("Instant Command 2");
|
||||
m_waitCommand.setName("Wait 5 Seconds Command");
|
||||
|
||||
// Set the scheduler to log Shuffleboard events for command initialize, interrupt, finish
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInitialize(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command initialized", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInterrupt(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command interrupted", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandFinish(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command finished", command.getName(), EventImportance.kNormal));
|
||||
|
||||
// Configure the button bindings
|
||||
configureButtonBindings();
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
// Run instant command 1 when the 'A' button is pressed
|
||||
new JoystickButton(m_driverController, Button.kA.value).onTrue(m_instantCommand1);
|
||||
// Run instant command 2 when the 'X' button is pressed
|
||||
new JoystickButton(m_driverController, Button.kX.value).onTrue(m_instantCommand2);
|
||||
// Run instant command 3 when the 'Y' button is held; release early to interrupt
|
||||
new JoystickButton(m_driverController, Button.kY.value).whileTrue(m_waitCommand);
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||
*
|
||||
* @return the command to run in autonomous
|
||||
*/
|
||||
public Command getAutonomousCommand() {
|
||||
return new InstantCommand();
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user