[examples] Hatchbots: Add telemetry (#5011)

This commit is contained in:
Starlight220
2023-02-01 09:44:18 +02:00
committed by GitHub
parent 83ef8f9658
commit 2f96cae31a
32 changed files with 251 additions and 568 deletions

View File

@@ -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

View File

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

View File

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

View File

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

View File

@@ -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.

View File

@@ -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.

View File

@@ -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

View File

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

View File

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

View File

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

View File

@@ -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.

View File

@@ -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.

View File

@@ -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

View File

@@ -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;
}

View File

@@ -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

View File

@@ -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;
};

View File

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

View File

@@ -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",