mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Add TimesliceRobot templates (#3683)
This commit is contained in:
@@ -41,6 +41,27 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Timeslice Robot",
|
||||
"description": "Timeslice style",
|
||||
"tags": [
|
||||
"Timeslice"
|
||||
],
|
||||
"foldername": "timeslice",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Timeslice Skeleton (Advanced)",
|
||||
"description": "Skeleton (stub) code for TimesliceRobot",
|
||||
"tags": [
|
||||
"Timeslice",
|
||||
"Skeleton"
|
||||
],
|
||||
"foldername": "timesliceskeleton",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "RobotBase Skeleton (Advanced)",
|
||||
"description": "Skeleton (stub) code for RobotBase - Not recommended for competition use",
|
||||
|
||||
@@ -0,0 +1,92 @@
|
||||
// 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 <fmt/core.h>
|
||||
#include <frc/livewindow/LiveWindow.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
// Run robot periodic() functions for 5 ms, and run controllers every 10 ms
|
||||
Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} {
|
||||
// LiveWindow causes drastic overruns in robot periodic functions that will
|
||||
// interfere with controllers
|
||||
frc::LiveWindow::DisableAllTelemetry();
|
||||
|
||||
// Runs for 2 ms after robot periodic functions
|
||||
Schedule([=] {}, 2_ms);
|
||||
|
||||
// Runs for 2 ms after first controller function
|
||||
Schedule([=] {}, 2_ms);
|
||||
|
||||
// Total usage:
|
||||
// 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2) = 9 ms
|
||||
// 9 ms / 10 ms -> 90% allocated
|
||||
}
|
||||
|
||||
void Robot::RobotInit() {
|
||||
m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
|
||||
m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
|
||||
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called every robot packet, 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.
|
||||
*/
|
||||
void Robot::RobotPeriodic() {}
|
||||
|
||||
/**
|
||||
* 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::AutonomousInit() {
|
||||
m_autoSelected = m_chooser.GetSelected();
|
||||
// m_autoSelected = SmartDashboard::GetString("Auto Selector",
|
||||
// kAutoNameDefault);
|
||||
fmt::print("Auto selected: {}\n", m_autoSelected);
|
||||
|
||||
if (m_autoSelected == kAutoNameCustom) {
|
||||
// Custom Auto goes here
|
||||
} else {
|
||||
// Default Auto goes here
|
||||
}
|
||||
}
|
||||
|
||||
void Robot::AutonomousPeriodic() {
|
||||
if (m_autoSelected == kAutoNameCustom) {
|
||||
// Custom Auto goes here
|
||||
} else {
|
||||
// Default Auto goes here
|
||||
}
|
||||
}
|
||||
|
||||
void Robot::TeleopInit() {}
|
||||
|
||||
void Robot::TeleopPeriodic() {}
|
||||
|
||||
void Robot::DisabledInit() {}
|
||||
|
||||
void Robot::DisabledPeriodic() {}
|
||||
|
||||
void Robot::TestInit() {}
|
||||
|
||||
void Robot::TestPeriodic() {}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -0,0 +1,32 @@
|
||||
// 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 <string>
|
||||
|
||||
#include <frc/TimesliceRobot.h>
|
||||
#include <frc/smartdashboard/SendableChooser.h>
|
||||
|
||||
class Robot : public frc::TimesliceRobot {
|
||||
public:
|
||||
Robot();
|
||||
|
||||
void RobotInit() override;
|
||||
void RobotPeriodic() override;
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
void DisabledInit() override;
|
||||
void DisabledPeriodic() override;
|
||||
void TestInit() override;
|
||||
void TestPeriodic() override;
|
||||
|
||||
private:
|
||||
frc::SendableChooser<std::string> m_chooser;
|
||||
const std::string kAutoNameDefault = "Default";
|
||||
const std::string kAutoNameCustom = "My Auto";
|
||||
std::string m_autoSelected;
|
||||
};
|
||||
@@ -0,0 +1,45 @@
|
||||
// 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/livewindow/LiveWindow.h>
|
||||
|
||||
// Run robot periodic() functions for 5 ms, and run controllers every 10 ms
|
||||
Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} {
|
||||
// LiveWindow causes drastic overruns in robot periodic functions that will
|
||||
// interfere with controllers
|
||||
frc::LiveWindow::DisableAllTelemetry();
|
||||
|
||||
// Runs for 2 ms after robot periodic functions
|
||||
Schedule([=] {}, 2_ms);
|
||||
|
||||
// Runs for 2 ms after first controller function
|
||||
Schedule([=] {}, 2_ms);
|
||||
|
||||
// Total usage:
|
||||
// 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2) = 9 ms
|
||||
// 9 ms / 10 ms -> 90% allocated
|
||||
}
|
||||
|
||||
void Robot::RobotInit() {}
|
||||
void Robot::RobotPeriodic() {}
|
||||
|
||||
void Robot::AutonomousInit() {}
|
||||
void Robot::AutonomousPeriodic() {}
|
||||
|
||||
void Robot::TeleopInit() {}
|
||||
void Robot::TeleopPeriodic() {}
|
||||
|
||||
void Robot::DisabledInit() {}
|
||||
void Robot::DisabledPeriodic() {}
|
||||
|
||||
void Robot::TestInit() {}
|
||||
void Robot::TestPeriodic() {}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -0,0 +1,27 @@
|
||||
// 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/TimesliceRobot.h>
|
||||
|
||||
class Robot : public frc::TimesliceRobot {
|
||||
public:
|
||||
Robot();
|
||||
|
||||
void RobotInit() override;
|
||||
void RobotPeriodic() override;
|
||||
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
|
||||
void DisabledInit() override;
|
||||
void DisabledPeriodic() override;
|
||||
|
||||
void TestInit() override;
|
||||
void TestPeriodic() override;
|
||||
};
|
||||
Reference in New Issue
Block a user