mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[examples] Clean up examples (#8674)
Move various "examples" into snippets. Several examples that were less than a full mechanism or robot were moved to snippets. `arcadedrive` and `tankdrive` were removed in favor of their Gamepad variants. `hidrumble` was removed due to being too simple. `potentiometerpid` was removed because of low utility. `gyromecanum` replaced `mecanumdrive` for deduplication and because very few teams run holonomic drivetrains without gyros.
This commit is contained in:
@@ -1,50 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
|
||||
import wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors
|
||||
in relation to the starting orientation of the robot (field-oriented controls).
|
||||
"""
|
||||
|
||||
kFrontLeftChannel = 0
|
||||
kRearLeftChannel = 1
|
||||
kFrontRightChannel = 2
|
||||
kRearRightChannel = 3
|
||||
kIMUMountOrientation = wpilib.OnboardIMU.MountOrientation.kFlat
|
||||
kJoystickPort = 0
|
||||
|
||||
def __init__(self) -> None:
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.imu = wpilib.OnboardIMU(self.kIMUMountOrientation)
|
||||
self.joystick = wpilib.Joystick(self.kJoystickPort)
|
||||
|
||||
frontLeft = wpilib.PWMSparkMax(self.kFrontLeftChannel)
|
||||
rearLeft = wpilib.PWMSparkMax(self.kRearLeftChannel)
|
||||
frontRight = wpilib.PWMSparkMax(self.kFrontRightChannel)
|
||||
rearRight = wpilib.PWMSparkMax(self.kRearRightChannel)
|
||||
|
||||
frontRight.setInverted(True)
|
||||
rearRight.setInverted(True)
|
||||
|
||||
self.robotDrive = wpilib.MecanumDrive(
|
||||
frontLeft, rearLeft, frontRight, rearRight
|
||||
)
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
self.robotDrive.driveCartesian(
|
||||
-self.joystick.getY(),
|
||||
-self.joystick.getX(),
|
||||
-self.joystick.getZ(),
|
||||
self.imu.getRotation2d(),
|
||||
)
|
||||
@@ -1,30 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
import wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a demo program showing the use of GenericHID's rumble feature.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.hid = wpilib.NiDsXboxController(0)
|
||||
|
||||
def autonomousInit(self):
|
||||
# Turn on rumble at the start of auto
|
||||
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kLeftRumble, 1.0)
|
||||
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kRightRumble, 1.0)
|
||||
|
||||
def disabledInit(self):
|
||||
# Stop the rumble when entering disabled
|
||||
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kLeftRumble, 0.0)
|
||||
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kRightRumble, 0.0)
|
||||
@@ -5,47 +5,46 @@
|
||||
# the WPILib BSD license file in the root directory of this project.
|
||||
#
|
||||
|
||||
|
||||
import wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a demo program showing how to use Mecanum control with the
|
||||
MecanumDrive class.
|
||||
This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors
|
||||
in relation to the starting orientation of the robot (field-oriented controls).
|
||||
"""
|
||||
|
||||
# Channels on the roboRIO that the motor controllers are plugged in to
|
||||
kFrontLeftChannel = 2
|
||||
kRearLeftChannel = 3
|
||||
kFrontRightChannel = 1
|
||||
kRearRightChannel = 0
|
||||
kFrontLeftChannel = 0
|
||||
kRearLeftChannel = 1
|
||||
kFrontRightChannel = 2
|
||||
kRearRightChannel = 3
|
||||
kIMUMountOrientation = wpilib.OnboardIMU.MountOrientation.kFlat
|
||||
kJoystickPort = 0
|
||||
|
||||
# The channel on the driver station that the joystick is connected to
|
||||
kJoystickChannel = 0
|
||||
|
||||
def __init__(self):
|
||||
def __init__(self) -> None:
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
self.frontLeft = wpilib.PWMSparkMax(self.kFrontLeftChannel)
|
||||
self.rearLeft = wpilib.PWMSparkMax(self.kRearLeftChannel)
|
||||
self.frontRight = wpilib.PWMSparkMax(self.kFrontRightChannel)
|
||||
self.rearRight = wpilib.PWMSparkMax(self.kRearRightChannel)
|
||||
|
||||
# invert the right side motors
|
||||
# you may need to change or remove this to match your robot
|
||||
self.frontRight.setInverted(True)
|
||||
self.rearRight.setInverted(True)
|
||||
self.imu = wpilib.OnboardIMU(self.kIMUMountOrientation)
|
||||
self.joystick = wpilib.Joystick(self.kJoystickPort)
|
||||
|
||||
frontLeft = wpilib.PWMSparkMax(self.kFrontLeftChannel)
|
||||
rearLeft = wpilib.PWMSparkMax(self.kRearLeftChannel)
|
||||
frontRight = wpilib.PWMSparkMax(self.kFrontRightChannel)
|
||||
rearRight = wpilib.PWMSparkMax(self.kRearRightChannel)
|
||||
|
||||
frontRight.setInverted(True)
|
||||
rearRight.setInverted(True)
|
||||
|
||||
self.robotDrive = wpilib.MecanumDrive(
|
||||
self.frontLeft, self.rearLeft, self.frontRight, self.rearRight
|
||||
frontLeft, rearLeft, frontRight, rearRight
|
||||
)
|
||||
|
||||
self.stick = wpilib.Joystick(self.kJoystickChannel)
|
||||
|
||||
def teleopPeriodic(self):
|
||||
# Use the joystick X axis for lateral movement, Y axis for forward
|
||||
# movement, and Z axis for rotation.
|
||||
def teleopPeriodic(self) -> None:
|
||||
self.robotDrive.driveCartesian(
|
||||
-self.stick.getY(),
|
||||
-self.stick.getX(),
|
||||
-self.stick.getZ(),
|
||||
-self.joystick.getY(),
|
||||
-self.joystick.getX(),
|
||||
-self.joystick.getZ(),
|
||||
self.imu.getRotation2d(),
|
||||
)
|
||||
|
||||
@@ -1,66 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
import wpilib
|
||||
import wpimath
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program to demonstrate how to use a soft potentiometer and a PID controller to
|
||||
reach and maintain position setpoints on an elevator mechanism.
|
||||
"""
|
||||
|
||||
kPotChannel = 1
|
||||
kMotorChannel = 7
|
||||
kJoystickChannel = 3
|
||||
|
||||
# The elevator can move 1.5 meters from top to bottom
|
||||
kFullHeightMeters = 1.5
|
||||
|
||||
# Bottom, middle, and top elevator setpoints
|
||||
kSetpointMeters = [0.2, 0.8, 1.4]
|
||||
|
||||
# proportional, integral, and derivative velocity constants
|
||||
# DANGER: when tuning PID constants, high/inappropriate values for kP, kI,
|
||||
# and kD may cause dangerous, uncontrollable, or undesired behavior!
|
||||
kP = 0.7
|
||||
kI = 0.35
|
||||
kD = 0.25
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
|
||||
self.pidController = wpimath.PIDController(self.kP, self.kI, self.kD)
|
||||
# Scaling is handled internally
|
||||
self.potentiometer = wpilib.AnalogPotentiometer(
|
||||
self.kPotChannel, self.kFullHeightMeters
|
||||
)
|
||||
self.elevatorMotor = wpilib.PWMSparkMax(self.kMotorChannel)
|
||||
self.joystick = wpilib.Joystick(self.kJoystickChannel)
|
||||
|
||||
def teleopInit(self):
|
||||
# Move to the bottom setpoint when teleop starts
|
||||
self.index = 0
|
||||
self.pidController.setSetpoint(self.kSetpointMeters[self.index])
|
||||
|
||||
def teleopPeriodic(self):
|
||||
# Read from the sensor
|
||||
position = self.potentiometer.get()
|
||||
|
||||
# Run the PID Controller
|
||||
pidOut = self.pidController.calculate(position)
|
||||
|
||||
# Apply PID output
|
||||
self.elevatorMotor.setDutyCycle(pidOut)
|
||||
|
||||
# when the button is pressed once, the selected elevator setpoint is incremented
|
||||
if self.joystick.getTriggerPressed():
|
||||
# index of the elevator setpoint wraps around.
|
||||
self.index = (self.index + 1) % len(self.kSetpointMeters)
|
||||
print(f"index = {self.index}")
|
||||
self.pidController.setSetpoint(self.kSetpointMeters[self.index])
|
||||
@@ -21,10 +21,8 @@ PROJECTS = [
|
||||
"FlywheelBangBangController",
|
||||
"GettingStarted",
|
||||
"Gyro",
|
||||
"GyroMecanum",
|
||||
"HatchbotInlined",
|
||||
"HatchbotTraditional",
|
||||
"HidRumble",
|
||||
"HttpCamera",
|
||||
"I2CCommunication",
|
||||
"IntermediateVision",
|
||||
@@ -33,7 +31,6 @@ PROJECTS = [
|
||||
"MecanumDrivePoseEstimator",
|
||||
"Mechanism2d",
|
||||
"MotorControl",
|
||||
"PotentiometerPID",
|
||||
"QuickVision",
|
||||
"RapidReactCommandBot",
|
||||
"RomiReference",
|
||||
|
||||
@@ -22,10 +22,8 @@ base = [
|
||||
"FlywheelBangBangController",
|
||||
"GettingStarted",
|
||||
"Gyro",
|
||||
"GyroMecanum",
|
||||
"HatchbotInlined",
|
||||
"HatchbotTraditional",
|
||||
"HidRumble",
|
||||
"HttpCamera",
|
||||
"I2CCommunication",
|
||||
"IntermediateVision",
|
||||
@@ -34,7 +32,6 @@ base = [
|
||||
"MecanumDrivePoseEstimator",
|
||||
"Mechanism2d",
|
||||
"MotorControl",
|
||||
"PotentiometerPID",
|
||||
"QuickVision",
|
||||
"RapidReactCommandBot",
|
||||
"RomiReference",
|
||||
|
||||
@@ -75,6 +75,35 @@ foreach(snippet ${SNIPPETS})
|
||||
add_executable(snippet${snippet} ${sources})
|
||||
wpilib_target_warnings(snippet${snippet})
|
||||
target_include_directories(snippet${snippet} PUBLIC src/main/cpp/snippets/${snippet}/include)
|
||||
target_link_libraries(snippet${snippet} wpilibc commandsv2 romiVendordep xrpVendordep)
|
||||
target_link_libraries(
|
||||
snippet${snippet}
|
||||
apriltag
|
||||
wpilibc
|
||||
commandsv2
|
||||
romiVendordep
|
||||
xrpVendordep
|
||||
)
|
||||
add_dependencies(wpilibcExamples_snippets snippet${snippet})
|
||||
|
||||
if(WITH_TESTS AND EXISTS ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/test/cpp/snippets/${snippet})
|
||||
wpilib_add_test(Snippet_${snippet} src/test/cpp/snippets/${snippet}/cpp)
|
||||
target_sources(Snippet_${snippet}_test PRIVATE ${sources})
|
||||
target_include_directories(
|
||||
Snippet_${snippet}_test
|
||||
PRIVATE
|
||||
src/main/cpp/snippets/${snippet}/include
|
||||
src/test/cpp/snippets/${snippet}/include
|
||||
)
|
||||
target_compile_definitions(Snippet_${snippet}_test PUBLIC RUNNING_WPILIB_TESTS)
|
||||
target_link_libraries(
|
||||
Snippet_${snippet}_test
|
||||
apriltag
|
||||
wpilibc
|
||||
commandsv2
|
||||
romiVendordep
|
||||
xrpVendordep
|
||||
googletest
|
||||
)
|
||||
add_dependencies(wpilibcExamples_test Snippet_${snippet}_test)
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
@@ -273,7 +273,7 @@ model {
|
||||
if (testFolder.exists()) {
|
||||
"snippets${key}Test"(GoogleTestTestSuiteSpec) {
|
||||
for (NativeComponentSpec c : $.components) {
|
||||
if (c.name == key) {
|
||||
if (c.name == "snippets${key}") {
|
||||
testing c
|
||||
break
|
||||
}
|
||||
@@ -281,20 +281,20 @@ model {
|
||||
sources {
|
||||
cpp {
|
||||
source {
|
||||
srcDirs "src/test/cpp/examples/${key}/cpp"
|
||||
srcDirs "src/test/cpp/snippets/${key}/cpp"
|
||||
include '**/*.cpp'
|
||||
}
|
||||
exportedHeaders {
|
||||
srcDirs "src/test/cpp/examples/${key}/include"
|
||||
srcDirs "src/test/cpp/snippets/${key}/include"
|
||||
}
|
||||
}
|
||||
c {
|
||||
source {
|
||||
srcDirs "src/test/cpp/examples/${key}/c"
|
||||
srcDirs "src/test/cpp/snippets/${key}/c"
|
||||
include '**/*.c'
|
||||
}
|
||||
exportedHeaders {
|
||||
srcDirs "src/test/cpp/examples/${key}/include"
|
||||
srcDirs "src/test/cpp/snippets/${key}/include"
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library", "cc_test")
|
||||
load("@rules_pkg//:mappings.bzl", "pkg_files")
|
||||
load("@rules_pkg//:pkg.bzl", "pkg_zip")
|
||||
load("//wpilibcExamples:example_projects.bzl", "COMMANDS_V2_FOLDERS", "EXAMPLE_FOLDERS", "SNIPPETS_FOLDERS", "TEMPLATES_FOLDERS", "TESTS_FOLDERS")
|
||||
load("//wpilibcExamples:example_projects.bzl", "COMMANDS_V2_FOLDERS", "EXAMPLE_FOLDERS", "EXAMPLE_TESTS_FOLDERS", "SNIPPET_FOLDERS", "SNIPPET_TESTS_FOLDERS", "TEMPLATE_FOLDERS")
|
||||
|
||||
def _package_type(package_type):
|
||||
pkg_files(
|
||||
@@ -40,11 +40,10 @@ def build_examples(halsim_deps = []):
|
||||
name = folder + "-example",
|
||||
srcs = native.glob(["src/main/cpp/examples/" + folder + "/cpp/**/*.cpp", "src/main/cpp/examples/" + folder + "/c/**/*.c"], allow_empty = True),
|
||||
deps = [
|
||||
"//commandsv2",
|
||||
"//apriltag",
|
||||
"//commandsv2",
|
||||
"//romiVendordep",
|
||||
"//xrpVendordep",
|
||||
"//cameraserver",
|
||||
":{}-examples-headers".format(folder),
|
||||
],
|
||||
tags = ["wpi-example"],
|
||||
@@ -68,13 +67,21 @@ def build_commands():
|
||||
def build_snippets():
|
||||
_package_type("snippets")
|
||||
|
||||
for folder in SNIPPETS_FOLDERS:
|
||||
for folder in SNIPPET_FOLDERS:
|
||||
cc_library(
|
||||
name = folder + "-template",
|
||||
name = folder + "-snippets-headers",
|
||||
hdrs = native.glob(["src/main/cpp/snippets/" + folder + "/include/**/*.hpp"], allow_empty = True),
|
||||
strip_include_prefix = "src/main/cpp/snippets/" + folder + "/include",
|
||||
tags = ["wpi-example"],
|
||||
)
|
||||
cc_library(
|
||||
name = folder + "-snippet",
|
||||
srcs = native.glob(["src/main/cpp/snippets/" + folder + "/**/*.cpp"]),
|
||||
hdrs = native.glob(["src/main/cpp/snippets/" + folder + "/**/*.hpp"], allow_empty = True),
|
||||
deps = [
|
||||
"//apriltag",
|
||||
"//commandsv2",
|
||||
"//cameraserver",
|
||||
":{}-snippets-headers".format(folder),
|
||||
],
|
||||
strip_include_prefix = "src/main/cpp/snippets/" + folder + "/include",
|
||||
tags = ["wpi-example"],
|
||||
@@ -83,7 +90,7 @@ def build_snippets():
|
||||
def build_templates():
|
||||
_package_type("templates")
|
||||
|
||||
for folder in TEMPLATES_FOLDERS:
|
||||
for folder in TEMPLATE_FOLDERS:
|
||||
cc_library(
|
||||
name = folder + "-template",
|
||||
srcs = native.glob(["src/main/cpp/templates/" + folder + "/**/*.cpp"]),
|
||||
@@ -96,7 +103,7 @@ def build_templates():
|
||||
)
|
||||
|
||||
def build_tests():
|
||||
for folder in TESTS_FOLDERS:
|
||||
for folder in EXAMPLE_TESTS_FOLDERS:
|
||||
example_src_folder = "src/main/cpp/examples/" + folder
|
||||
example_test_folder = "src/test/cpp/examples/" + folder
|
||||
cc_test(
|
||||
@@ -111,3 +118,18 @@ def build_tests():
|
||||
defines = ["RUNNING_WPILIB_TESTS=1"],
|
||||
tags = ["wpi-example", "no-tsan", "no-asan", "no-ubsan", "exclusive"],
|
||||
)
|
||||
for folder in SNIPPET_TESTS_FOLDERS:
|
||||
snippet_src_folder = "src/main/cpp/snippets/" + folder
|
||||
snippet_test_folder = "src/test/cpp/snippets/" + folder
|
||||
cc_test(
|
||||
name = folder + "-test",
|
||||
size = "small",
|
||||
srcs = native.glob([snippet_test_folder + "/**/*.cpp", snippet_src_folder + "/**/*.cpp"], allow_empty = True),
|
||||
deps = [
|
||||
"//commandsv2",
|
||||
":{}-snippets-headers".format(folder),
|
||||
"//thirdparty/googletest",
|
||||
],
|
||||
defines = ["RUNNING_WPILIB_TESTS=1"],
|
||||
tags = ["wpi-example", "no-tsan", "no-asan", "no-ubsan", "exclusive"],
|
||||
)
|
||||
|
||||
@@ -1,46 +1,28 @@
|
||||
EXAMPLE_FOLDERS = [
|
||||
"AddressableLED",
|
||||
"AprilTagsVision",
|
||||
"ArcadeDrive",
|
||||
"ArcadeDriveGamepad",
|
||||
"ArmSimulation",
|
||||
"CANPDP",
|
||||
"DifferentialDriveBot",
|
||||
"DifferentialDrivePoseEstimator",
|
||||
"DigitalCommunication",
|
||||
"DriveDistanceOffboard",
|
||||
"DutyCycleEncoder",
|
||||
"DutyCycleInput",
|
||||
"ElevatorExponentialProfile",
|
||||
"ElevatorExponentialSimulation",
|
||||
"ElevatorProfiledPID",
|
||||
"ElevatorSimulation",
|
||||
"ElevatorTrapezoidProfile",
|
||||
"Encoder",
|
||||
"EventLoop",
|
||||
"FlywheelBangBangController",
|
||||
"GettingStarted",
|
||||
"Gyro",
|
||||
"GyroMecanum",
|
||||
"HAL",
|
||||
"HatchbotInlined",
|
||||
"HatchbotTraditional",
|
||||
"HidRumble",
|
||||
"HttpCamera",
|
||||
"I2CCommunication",
|
||||
"IntermediateVision",
|
||||
"MecanumBot",
|
||||
"MecanumDrive",
|
||||
"MecanumDrivePoseEstimator",
|
||||
"Mechanism2d",
|
||||
"MotorControl",
|
||||
"PotentiometerPID",
|
||||
"QuickVision",
|
||||
"RapidReactCommandBot",
|
||||
"RomiReference",
|
||||
"SelectCommand",
|
||||
"SimpleDifferentialDriveSimulation",
|
||||
"Solenoid",
|
||||
"StateSpaceArm",
|
||||
"StateSpaceElevator",
|
||||
"StateSpaceFlywheel",
|
||||
@@ -48,7 +30,6 @@ EXAMPLE_FOLDERS = [
|
||||
"SwerveBot",
|
||||
"SwerveDrivePoseEstimator",
|
||||
"SysIdRoutine",
|
||||
"TankDrive",
|
||||
"TankDriveGamepad",
|
||||
"UnitTest",
|
||||
"XRPReference",
|
||||
@@ -66,25 +47,39 @@ COMMANDS_V2_FOLDERS = [
|
||||
"subsystem2",
|
||||
]
|
||||
|
||||
SNIPPETS_FOLDERS = [
|
||||
SNIPPET_FOLDERS = [
|
||||
"ADXLAccelerometers",
|
||||
"AccelerometerCollision",
|
||||
"AccelerometerFilter",
|
||||
"AddressableLED",
|
||||
"AnalogAccelerometer",
|
||||
"AnalogEncoder",
|
||||
"AnalogInput",
|
||||
"AnalogPotentiometer",
|
||||
"AprilTagsVision",
|
||||
"CANPDP",
|
||||
"DigitalCommunication",
|
||||
"DigitalInput",
|
||||
"DutyCycleEncoder",
|
||||
"DutyCycleInput",
|
||||
"Encoder",
|
||||
"EncoderDrive",
|
||||
"EncoderHoming",
|
||||
"EventLoop",
|
||||
"FlywheelBangBangController",
|
||||
"HttpCamera",
|
||||
"I2CCommunication",
|
||||
"IntermediateVision",
|
||||
"LimitSwitch",
|
||||
"MotorControl",
|
||||
"OnboardIMU",
|
||||
"ProfiledPIDFeedforward",
|
||||
"QuickVision",
|
||||
"SelectCommand",
|
||||
"Solenoid",
|
||||
]
|
||||
|
||||
TEMPLATES_FOLDERS = [
|
||||
TEMPLATE_FOLDERS = [
|
||||
"commandv2",
|
||||
"commandv2skeleton",
|
||||
"opmode",
|
||||
@@ -95,11 +90,13 @@ TEMPLATES_FOLDERS = [
|
||||
"timesliceskeleton",
|
||||
]
|
||||
|
||||
TESTS_FOLDERS = [
|
||||
EXAMPLE_TESTS_FOLDERS = [
|
||||
"ArmSimulation",
|
||||
"DigitalCommunication",
|
||||
"ElevatorSimulation",
|
||||
"I2CCommunication",
|
||||
"PotentiometerPID",
|
||||
"UnitTest",
|
||||
]
|
||||
|
||||
SNIPPET_TESTS_FOLDERS = [
|
||||
"DigitalCommunication",
|
||||
"I2CCommunication",
|
||||
]
|
||||
|
||||
@@ -34,7 +34,8 @@ def main():
|
||||
"wpilibcExamples/src/main/cpp/templates/templates.json"
|
||||
)
|
||||
snippets = load_foldernames("wpilibcExamples/src/main/cpp/snippets/snippets.json")
|
||||
tests = load_tests("wpilibcExamples/src/main/cpp/examples/examples.json")
|
||||
example_tests = load_tests("wpilibcExamples/src/main/cpp/examples/examples.json")
|
||||
snippet_tests = load_tests("wpilibcExamples/src/main/cpp/snippets/snippets.json")
|
||||
|
||||
output_file = "wpilibcExamples/example_projects.bzl"
|
||||
if len(sys.argv) == 2:
|
||||
@@ -45,13 +46,20 @@ def main():
|
||||
f.write(
|
||||
'COMMANDS_V2_FOLDERS = [\n "' + '",\n "'.join(commands) + '",\n]\n\n'
|
||||
)
|
||||
f.write('SNIPPET_FOLDERS = [\n "' + '",\n "'.join(snippets) + '",\n]\n\n')
|
||||
f.write(
|
||||
'SNIPPETS_FOLDERS = [\n "' + '",\n "'.join(snippets) + '",\n]\n\n'
|
||||
'TEMPLATE_FOLDERS = [\n "' + '",\n "'.join(templates) + '",\n]\n\n'
|
||||
)
|
||||
f.write(
|
||||
'TEMPLATES_FOLDERS = [\n "' + '",\n "'.join(templates) + '",\n]\n\n'
|
||||
'EXAMPLE_TESTS_FOLDERS = [\n "'
|
||||
+ '",\n "'.join(example_tests)
|
||||
+ '",\n]\n\n'
|
||||
)
|
||||
f.write(
|
||||
'SNIPPET_TESTS_FOLDERS = [\n "'
|
||||
+ '",\n "'.join(snippet_tests)
|
||||
+ '",\n]\n'
|
||||
)
|
||||
f.write('TESTS_FOLDERS = [\n "' + '",\n "'.join(tests) + '",\n]\n')
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
@@ -1,43 +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 "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/Joystick.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with arcade steering.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
wpi::PWMSparkMax m_leftMotor{0};
|
||||
wpi::PWMSparkMax m_rightMotor{1};
|
||||
wpi::DifferentialDrive m_robotDrive{
|
||||
[&](double output) { m_leftMotor.SetDutyCycle(output); },
|
||||
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
|
||||
wpi::Joystick m_stick{0};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
|
||||
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Drive with arcade style
|
||||
m_robotDrive.ArcadeDrive(-m_stick.GetY(), -m_stick.GetX());
|
||||
}
|
||||
};
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
int main() {
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,65 +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 "wpi/drive/MecanumDrive.hpp"
|
||||
#include "wpi/driverstation/Joystick.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/imu/OnboardIMU.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to
|
||||
* maintain rotation vectors in relation to the starting orientation of the
|
||||
* robot (field-oriented controls).
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
Robot() {
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
|
||||
|
||||
// Invert the right side motors. You may need to change or remove this to
|
||||
// match your robot.
|
||||
m_frontRight.SetInverted(true);
|
||||
m_rearRight.SetInverted(true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Mecanum drive is used with the gyro angle as an input.
|
||||
*/
|
||||
void TeleopPeriodic() override {
|
||||
m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
|
||||
-m_joystick.GetZ(), m_imu.GetRotation2d());
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr int kFrontLeftMotorPort = 0;
|
||||
static constexpr int kRearLeftMotorPort = 1;
|
||||
static constexpr int kFrontRightMotorPort = 2;
|
||||
static constexpr int kRearRightMotorPort = 3;
|
||||
static constexpr wpi::OnboardIMU::MountOrientation kIMUMountOrientation =
|
||||
wpi::OnboardIMU::kFlat;
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
wpi::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
|
||||
wpi::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
|
||||
wpi::PWMSparkMax m_frontRight{kFrontRightMotorPort};
|
||||
wpi::PWMSparkMax m_rearRight{kRearRightMotorPort};
|
||||
wpi::MecanumDrive m_robotDrive{
|
||||
[&](double output) { m_frontLeft.SetDutyCycle(output); },
|
||||
[&](double output) { m_rearLeft.SetDutyCycle(output); },
|
||||
[&](double output) { m_frontRight.SetDutyCycle(output); },
|
||||
[&](double output) { m_rearRight.SetDutyCycle(output); }};
|
||||
|
||||
wpi::OnboardIMU m_imu{kIMUMountOrientation};
|
||||
wpi::Joystick m_joystick{kJoystickPort};
|
||||
};
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
int main() {
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,33 +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 "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of GenericHID's rumble feature.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
void AutonomousInit() override {
|
||||
// Turn on rumble at the start of auto
|
||||
m_hid.SetRumble(wpi::GenericHID::RumbleType::kLeftRumble, 1.0);
|
||||
m_hid.SetRumble(wpi::GenericHID::RumbleType::kRightRumble, 1.0);
|
||||
}
|
||||
|
||||
void DisabledInit() override {
|
||||
// Stop the rumble when entering disabled
|
||||
m_hid.SetRumble(wpi::GenericHID::RumbleType::kLeftRumble, 0.0);
|
||||
m_hid.SetRumble(wpi::GenericHID::RumbleType::kRightRumble, 0.0);
|
||||
}
|
||||
|
||||
private:
|
||||
wpi::GenericHID m_hid{0};
|
||||
};
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
int main() {
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -5,11 +5,13 @@
|
||||
#include "wpi/drive/MecanumDrive.hpp"
|
||||
#include "wpi/driverstation/Joystick.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/imu/OnboardIMU.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing how to use Mecanum control with the
|
||||
* MecanumDrive class.
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to
|
||||
* maintain rotation vectors in relation to the starting orientation of the
|
||||
* robot (field-oriented controls).
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
@@ -25,33 +27,38 @@ class Robot : public wpi::TimedRobot {
|
||||
m_rearRight.SetInverted(true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Mecanum drive is used with the gyro angle as an input.
|
||||
*/
|
||||
void TeleopPeriodic() override {
|
||||
/* Use the joystick Y axis for forward movement, X axis for lateral
|
||||
* movement, and Z axis for rotation.
|
||||
*/
|
||||
m_robotDrive.DriveCartesian(-m_stick.GetY(), -m_stick.GetX(),
|
||||
-m_stick.GetZ());
|
||||
m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
|
||||
-m_joystick.GetZ(), m_imu.GetRotation2d());
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr int kFrontLeftChannel = 0;
|
||||
static constexpr int kRearLeftChannel = 1;
|
||||
static constexpr int kFrontRightChannel = 2;
|
||||
static constexpr int kRearRightChannel = 3;
|
||||
static constexpr int kFrontLeftMotorPort = 0;
|
||||
static constexpr int kRearLeftMotorPort = 1;
|
||||
static constexpr int kFrontRightMotorPort = 2;
|
||||
static constexpr int kRearRightMotorPort = 3;
|
||||
static constexpr wpi::OnboardIMU::MountOrientation kIMUMountOrientation =
|
||||
wpi::OnboardIMU::kFlat;
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
static constexpr int kJoystickChannel = 0;
|
||||
|
||||
wpi::PWMSparkMax m_frontLeft{kFrontLeftChannel};
|
||||
wpi::PWMSparkMax m_rearLeft{kRearLeftChannel};
|
||||
wpi::PWMSparkMax m_frontRight{kFrontRightChannel};
|
||||
wpi::PWMSparkMax m_rearRight{kRearRightChannel};
|
||||
wpi::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
|
||||
wpi::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
|
||||
wpi::PWMSparkMax m_frontRight{kFrontRightMotorPort};
|
||||
wpi::PWMSparkMax m_rearRight{kRearRightMotorPort};
|
||||
wpi::MecanumDrive m_robotDrive{
|
||||
[&](double output) { m_frontLeft.SetDutyCycle(output); },
|
||||
[&](double output) { m_rearLeft.SetDutyCycle(output); },
|
||||
[&](double output) { m_frontRight.SetDutyCycle(output); },
|
||||
[&](double output) { m_rearRight.SetDutyCycle(output); }};
|
||||
|
||||
wpi::Joystick m_stick{kJoystickChannel};
|
||||
wpi::OnboardIMU m_imu{kIMUMountOrientation};
|
||||
wpi::Joystick m_joystick{kJoystickPort};
|
||||
};
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
|
||||
@@ -1,36 +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.hpp"
|
||||
|
||||
void Robot::TeleopInit() {
|
||||
// Move to the bottom setpoint when teleop starts
|
||||
m_index = 0;
|
||||
m_pidController.SetSetpoint(kSetpoints[m_index].value());
|
||||
}
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
// Read from the sensor
|
||||
wpi::units::meter_t position = wpi::units::meter_t{m_potentiometer.Get()};
|
||||
|
||||
// Run the PID Controller
|
||||
double pidOut = m_pidController.Calculate(position.value());
|
||||
|
||||
// Apply PID output
|
||||
m_elevatorMotor.SetDutyCycle(pidOut);
|
||||
|
||||
// when the button is pressed once, the selected elevator setpoint is
|
||||
// incremented
|
||||
if (m_joystick.GetTriggerPressed()) {
|
||||
// index of the elevator setpoint wraps around.
|
||||
m_index = (m_index + 1) % kSetpoints.size();
|
||||
m_pidController.SetSetpoint(kSetpoints[m_index].value());
|
||||
}
|
||||
}
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
int main() {
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,55 +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 <array>
|
||||
|
||||
#include "wpi/driverstation/Joystick.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/AnalogPotentiometer.hpp"
|
||||
#include "wpi/math/controller/PIDController.hpp"
|
||||
#include "wpi/units/length.hpp"
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a soft potentiometer and a
|
||||
* PID controller to reach and maintain position setpoints on an elevator
|
||||
* mechanism.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
|
||||
static constexpr int kPotChannel = 1;
|
||||
static constexpr int kMotorChannel = 7;
|
||||
static constexpr int kJoystickChannel = 3;
|
||||
|
||||
// The elevator can move 1.5 meters from top to bottom
|
||||
static constexpr wpi::units::meter_t kFullHeight = 1.5_m;
|
||||
|
||||
// Bottom, middle, and top elevator setpoints
|
||||
static constexpr std::array<wpi::units::meter_t, 3> kSetpoints = {
|
||||
{0.2_m, 0.8_m, 1.4_m}};
|
||||
|
||||
private:
|
||||
// proportional velocity constant
|
||||
// negative because applying positive voltage will bring us closer to the
|
||||
// target
|
||||
static constexpr double kP = 0.7;
|
||||
// integral velocity constant
|
||||
static constexpr double kI = 0.35;
|
||||
// derivative velocity constant
|
||||
static constexpr double kD = 0.25;
|
||||
|
||||
// Scaling is handled internally
|
||||
wpi::AnalogPotentiometer m_potentiometer{kPotChannel, kFullHeight.value()};
|
||||
|
||||
wpi::PWMSparkMax m_elevatorMotor{kMotorChannel};
|
||||
wpi::math::PIDController m_pidController{kP, kI, kD};
|
||||
wpi::Joystick m_joystick{kJoystickChannel};
|
||||
|
||||
size_t m_index;
|
||||
};
|
||||
@@ -1,44 +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 "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/Joystick.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with tank steering.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
wpi::PWMSparkMax m_leftMotor{0};
|
||||
wpi::PWMSparkMax m_rightMotor{1};
|
||||
wpi::DifferentialDrive m_robotDrive{
|
||||
[&](double output) { m_leftMotor.SetDutyCycle(output); },
|
||||
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
|
||||
wpi::Joystick m_leftStick{0};
|
||||
wpi::Joystick m_rightStick{1};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
|
||||
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
|
||||
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Drive with tank style
|
||||
m_robotDrive.TankDrive(-m_leftStick.GetY(), -m_rightStick.GetY());
|
||||
}
|
||||
};
|
||||
|
||||
#ifndef RUNNING_WPILIB_TESTS
|
||||
int main() {
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,29 +1,4 @@
|
||||
[
|
||||
{
|
||||
"name": "Motor Control",
|
||||
"description": "Control a single motor with a joystick, displaying the movement of the motor using an encoder.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Encoder",
|
||||
"SmartDashboard",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "MotorControl",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "PDP CAN Monitoring",
|
||||
"description": "Monitor Power Distribution data such as voltage, current, temperature, etc.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"PDP",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "CANPDP",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Mechanism2d",
|
||||
"foldername": "Mechanism2d",
|
||||
@@ -40,18 +15,6 @@
|
||||
],
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Solenoids",
|
||||
"description": "Control a single and double solenoid from joystick buttons.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "Solenoid",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Encoder",
|
||||
"description": "View values from a quadrature encoder.",
|
||||
@@ -64,54 +27,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "EventLoop",
|
||||
"description": "Manage a ball system using EventLoop and BooleanEvent.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Flywheel",
|
||||
"EventLoop"
|
||||
],
|
||||
"foldername": "EventLoop",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Arcade Drive",
|
||||
"description": "Control a differential drivetrain with single-joystick arcade drive in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "ArcadeDrive",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Tank Drive",
|
||||
"description": "Control a differential drive with twin-joystick tank drive in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "TankDrive",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Mecanum Drive",
|
||||
"description": "Control a mecanum drivetrain with a joystick in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Mecanum Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "MecanumDrive",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Gyro",
|
||||
"description": "Drive a differential drive straight with a gyro sensor.",
|
||||
@@ -120,7 +35,6 @@
|
||||
"Differential Drive",
|
||||
"PID",
|
||||
"Gyro",
|
||||
"Analog",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "Gyro",
|
||||
@@ -128,45 +42,18 @@
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Gyro Mecanum",
|
||||
"name": "Mecanum Drive",
|
||||
"description": "Drive a mecanum drivetrain using field-oriented controls with a joystick.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Mecanum Drive",
|
||||
"Gyro",
|
||||
"Analog",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "GyroMecanum",
|
||||
"foldername": "MecanumDrive",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "HID Rumble",
|
||||
"description": "Make human interface devices (HID) rumble.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "HidRumble",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "PotentiometerPID",
|
||||
"description": "Maintain elevator position setpoints with a potentiometer and PID control.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Analog",
|
||||
"Elevator",
|
||||
"PID",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "PotentiometerPID",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2,
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Elevator with exponential profiled PID",
|
||||
"description": "Reach elevator position setpoints with exponential profiles and smart motor controller PID.",
|
||||
@@ -218,71 +105,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Simple Vision",
|
||||
"description": "Use the CameraServer class to stream from a USB Webcam without processing the images.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "QuickVision",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Intermediate Vision",
|
||||
"description": "Acquire images from an attached USB camera and add some annotation to the image (as you might do for showing operators the result of some image recognition) and send it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "IntermediateVision",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "AprilTags Vision",
|
||||
"description": "On-roboRIO detection of AprilTags using an attached USB camera.",
|
||||
"tags": [
|
||||
"Vision",
|
||||
"AprilTags"
|
||||
],
|
||||
"foldername": "AprilTagsVision",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "I2C Communication",
|
||||
"description": "Communicate with external devices (such as an Arduino) using the roboRIO's I2C port.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"I2C"
|
||||
],
|
||||
"foldername": "I2CCommunication",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2,
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Digital Communication Sample",
|
||||
"description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Digital Output"
|
||||
],
|
||||
"foldername": "DigitalCommunication",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2,
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "HTTP Camera",
|
||||
"description": "Acquire images from an HTTP network camera and adds some annotation to the image (as you might do for showing operators the result of some image recognition), and sends it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "HttpCamera",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "HAL",
|
||||
"description": "Use the low-level HAL C functions. This example is for advanced users.",
|
||||
@@ -349,16 +171,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Select Command Example",
|
||||
"description": "Use SelectCommand to select an autonomous routine.",
|
||||
"tags": [
|
||||
"Commandv2"
|
||||
],
|
||||
"foldername": "SelectCommand",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "SwerveBot",
|
||||
"description": "Use kinematics and odometry with a swerve drive.",
|
||||
@@ -438,30 +250,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Duty Cycle Input",
|
||||
"description": "View duty-cycle input.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Duty Cycle",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "DutyCycleInput",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Addressable LED",
|
||||
"description": "Display a rainbow pattern on an addressable LED strip.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Basic Robot",
|
||||
"AddressableLEDs"
|
||||
],
|
||||
"foldername": "AddressableLED",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "DriveDistanceOffboard",
|
||||
"description": "Drive a differential drivetrain a set distance using TrapezoidProfile and smart motor controller PID.",
|
||||
@@ -707,18 +495,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Flywheel BangBangController",
|
||||
"description": "A sample program to demonstrate the use of a BangBangController with a flywheel to control RPM",
|
||||
"tags": [
|
||||
"Flywheel",
|
||||
"Simulation",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "FlywheelBangBangController",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "SysIdRoutine",
|
||||
"description": "A sample Commandv2 robot demonstrating use of the SysIdRoutine command factory",
|
||||
|
||||
@@ -156,5 +156,152 @@
|
||||
],
|
||||
"foldername": "ProfiledPIDFeedforward",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Addressable LED",
|
||||
"description": "Display a rainbow pattern on an addressable LED strip.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Basic Robot",
|
||||
"AddressableLEDs"
|
||||
],
|
||||
"foldername": "AddressableLED",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "AprilTags Vision",
|
||||
"description": "On-roboRIO detection of AprilTags using an attached USB camera.",
|
||||
"tags": [
|
||||
"Vision",
|
||||
"AprilTags"
|
||||
],
|
||||
"foldername": "AprilTagsVision",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "PDP CAN Monitoring",
|
||||
"description": "Monitor Power Distribution data such as voltage, current, temperature, etc.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"PDP",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "CANPDP",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Digital Communication Sample",
|
||||
"description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Digital Output"
|
||||
],
|
||||
"foldername": "DigitalCommunication",
|
||||
"gradlebase": "cpp",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Duty Cycle Input",
|
||||
"description": "View duty-cycle input.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Duty Cycle",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "DutyCycleInput",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "EventLoop",
|
||||
"description": "Manage a ball system using EventLoop and BooleanEvent.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Flywheel",
|
||||
"EventLoop"
|
||||
],
|
||||
"foldername": "EventLoop",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Flywheel BangBangController",
|
||||
"description": "A sample program to demonstrate the use of a BangBangController with a flywheel to control RPM",
|
||||
"tags": [
|
||||
"Flywheel",
|
||||
"Simulation",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "FlywheelBangBangController",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "HTTP Camera",
|
||||
"description": "Acquire images from an HTTP network camera and adds some annotation to the image (as you might do for showing operators the result of some image recognition), and sends it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "HttpCamera",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "I2C Communication",
|
||||
"description": "Communicate with external devices (such as an Arduino) using the roboRIO's I2C port.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"I2C"
|
||||
],
|
||||
"foldername": "I2CCommunication",
|
||||
"gradlebase": "cpp",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Intermediate Vision",
|
||||
"description": "Acquire images from an attached USB camera and add some annotation to the image (as you might do for showing operators the result of some image recognition) and send it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "IntermediateVision",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Motor Control",
|
||||
"description": "Control a single motor with a joystick, displaying the movement of the motor using an encoder.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Encoder",
|
||||
"SmartDashboard",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "MotorControl",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Select Command Example",
|
||||
"description": "Use SelectCommand to select an autonomous routine.",
|
||||
"tags": [
|
||||
"Commandv2"
|
||||
],
|
||||
"foldername": "SelectCommand",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Simple Vision",
|
||||
"description": "Use the CameraServer class to stream from a USB Webcam without processing the images.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "QuickVision",
|
||||
"gradlebase": "cpp"
|
||||
},
|
||||
{
|
||||
"name": "Solenoids",
|
||||
"description": "Control a single and double solenoid from joystick buttons.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "Solenoid",
|
||||
"gradlebase": "cpp"
|
||||
}
|
||||
]
|
||||
|
||||
@@ -1,166 +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 <thread>
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
#include "Robot.hpp"
|
||||
#include "wpi/hal/DriverStationTypes.h"
|
||||
#include "wpi/hal/simulation/MockHooks.h"
|
||||
#include "wpi/math/system/DCMotor.hpp"
|
||||
#include "wpi/simulation/AnalogInputSim.hpp"
|
||||
#include "wpi/simulation/DriverStationSim.hpp"
|
||||
#include "wpi/simulation/ElevatorSim.hpp"
|
||||
#include "wpi/simulation/JoystickSim.hpp"
|
||||
#include "wpi/simulation/PWMMotorControllerSim.hpp"
|
||||
#include "wpi/simulation/SimHooks.hpp"
|
||||
#include "wpi/system/RobotController.hpp"
|
||||
#include "wpi/units/length.hpp"
|
||||
#include "wpi/units/mass.hpp"
|
||||
#include "wpi/units/time.hpp"
|
||||
|
||||
class PotentiometerPIDTest : public testing::Test {
|
||||
wpi::math::DCMotor m_elevatorGearbox = wpi::math::DCMotor::Vex775Pro(4);
|
||||
static constexpr double kElevatorGearing = 10.0;
|
||||
static constexpr wpi::units::meter_t kElevatorDrumRadius = 2.0_in;
|
||||
static constexpr wpi::units::kilogram_t kCarriageMass = 4.0_kg;
|
||||
|
||||
Robot m_robot;
|
||||
std::optional<std::thread> m_thread;
|
||||
|
||||
protected:
|
||||
wpi::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
|
||||
kElevatorGearing,
|
||||
kCarriageMass,
|
||||
kElevatorDrumRadius,
|
||||
0.0_m,
|
||||
Robot::kFullHeight,
|
||||
true,
|
||||
0.0_m};
|
||||
wpi::sim::PWMMotorControllerSim m_motorSim{Robot::kMotorChannel};
|
||||
wpi::sim::AnalogInputSim m_analogSim{Robot::kPotChannel};
|
||||
wpi::sim::JoystickSim m_joystickSim{Robot::kJoystickChannel};
|
||||
int32_t m_callback;
|
||||
int32_t m_port;
|
||||
|
||||
public:
|
||||
void SimPeriodicBefore() {
|
||||
m_elevatorSim.SetInputVoltage(m_motorSim.GetDutyCycle() *
|
||||
wpi::RobotController::GetBatteryVoltage());
|
||||
m_elevatorSim.Update(20_ms);
|
||||
|
||||
/*
|
||||
meters = (v / 3.3v) * range
|
||||
meters / range = v / 3.3v
|
||||
3.3v * (meters / range) = v
|
||||
*/
|
||||
m_analogSim.SetVoltage(
|
||||
(wpi::RobotController::GetVoltage3V3() *
|
||||
(m_elevatorSim.GetPosition().value() / Robot::kFullHeight))
|
||||
.value());
|
||||
}
|
||||
|
||||
static void CallSimPeriodicBefore(void* param) {
|
||||
static_cast<PotentiometerPIDTest*>(param)->SimPeriodicBefore();
|
||||
}
|
||||
|
||||
void SetUp() override {
|
||||
wpi::sim::PauseTiming();
|
||||
wpi::sim::SetProgramStarted(false);
|
||||
wpi::sim::DriverStationSim::ResetData();
|
||||
|
||||
m_joystickSim.SetButtonsMaximumIndex(12);
|
||||
|
||||
m_callback =
|
||||
HALSIM_RegisterSimPeriodicBeforeCallback(CallSimPeriodicBefore, this);
|
||||
|
||||
m_thread = std::thread([&] { m_robot.StartCompetition(); });
|
||||
wpi::sim::WaitForProgramStart();
|
||||
}
|
||||
|
||||
void TearDown() override {
|
||||
m_robot.EndCompetition();
|
||||
m_thread->join();
|
||||
|
||||
HALSIM_CancelSimPeriodicBeforeCallback(m_callback);
|
||||
m_analogSim.ResetData();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(PotentiometerPIDTest, Teleop) {
|
||||
// teleop init
|
||||
{
|
||||
wpi::sim::DriverStationSim::SetRobotMode(HAL_ROBOTMODE_TELEOPERATED);
|
||||
wpi::sim::DriverStationSim::SetEnabled(true);
|
||||
wpi::sim::DriverStationSim::NotifyNewData();
|
||||
|
||||
EXPECT_TRUE(m_analogSim.GetInitialized());
|
||||
}
|
||||
|
||||
// first setpoint
|
||||
{
|
||||
// advance 50 timesteps
|
||||
wpi::sim::StepTiming(1_s);
|
||||
|
||||
EXPECT_NEAR(Robot::kSetpoints[0].value(),
|
||||
m_elevatorSim.GetPosition().value(), 0.1);
|
||||
}
|
||||
|
||||
// second setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.SetTrigger(true);
|
||||
m_joystickSim.NotifyNewData();
|
||||
|
||||
// advance 50 timesteps
|
||||
wpi::sim::StepTiming(1_s);
|
||||
|
||||
EXPECT_NEAR(Robot::kSetpoints[1].value(),
|
||||
m_elevatorSim.GetPosition().value(), 0.1);
|
||||
}
|
||||
|
||||
// we need to unpress the button
|
||||
{
|
||||
m_joystickSim.SetTrigger(false);
|
||||
m_joystickSim.NotifyNewData();
|
||||
|
||||
// advance 10 timesteps
|
||||
wpi::sim::StepTiming(0.2_s);
|
||||
}
|
||||
|
||||
// third setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.SetTrigger(true);
|
||||
m_joystickSim.NotifyNewData();
|
||||
|
||||
// advance 50 timesteps
|
||||
wpi::sim::StepTiming(1_s);
|
||||
|
||||
EXPECT_NEAR(Robot::kSetpoints[2].value(),
|
||||
m_elevatorSim.GetPosition().value(), 0.1);
|
||||
}
|
||||
|
||||
// we need to unpress the button
|
||||
{
|
||||
m_joystickSim.SetTrigger(false);
|
||||
m_joystickSim.NotifyNewData();
|
||||
|
||||
// advance 10 timesteps
|
||||
wpi::sim::StepTiming(0.2_s);
|
||||
}
|
||||
|
||||
// rollover: first setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.SetTrigger(true);
|
||||
m_joystickSim.NotifyNewData();
|
||||
|
||||
// advance 60 timesteps
|
||||
wpi::sim::StepTiming(1.2_s);
|
||||
EXPECT_NEAR(Robot::kSetpoints[0].value(),
|
||||
m_elevatorSim.GetPosition().value(), 0.1);
|
||||
}
|
||||
}
|
||||
@@ -1,17 +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 <gtest/gtest.h>
|
||||
|
||||
#include "wpi/hal/HAL.h"
|
||||
|
||||
/**
|
||||
* Runs all unit tests.
|
||||
*/
|
||||
int main(int argc, char** argv) {
|
||||
HAL_Initialize(500, 0);
|
||||
::testing::InitGoogleTest(&argc, argv);
|
||||
int ret = RUN_ALL_TESTS();
|
||||
return ret;
|
||||
}
|
||||
@@ -2,7 +2,7 @@ load("@rules_java//java:defs.bzl", "java_binary", "java_library")
|
||||
load("@rules_pkg//:mappings.bzl", "pkg_files")
|
||||
load("@rules_pkg//:pkg.bzl", "pkg_zip")
|
||||
load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test")
|
||||
load("//wpilibjExamples:example_projects.bzl", "COMMANDS_V2_FOLDERS", "EXAMPLES_FOLDERS", "SNIPPETS_FOLDERS", "TEMPLATES_FOLDERS", "TEST_FOLDERS")
|
||||
load("//wpilibjExamples:example_projects.bzl", "COMMANDS_V2_FOLDERS", "EXAMPLE_FOLDERS", "EXAMPLE_TESTS_FOLDERS", "SNIPPET_FOLDERS", "SNIPPET_TESTS_FOLDERS", "TEMPLATE_FOLDERS")
|
||||
|
||||
def _package_type(package_type):
|
||||
pkg_files(
|
||||
@@ -30,7 +30,7 @@ def _package_type(package_type):
|
||||
def build_examples(halsim_deps):
|
||||
_package_type("examples")
|
||||
|
||||
for folder in EXAMPLES_FOLDERS:
|
||||
for folder in EXAMPLE_FOLDERS:
|
||||
java_binary(
|
||||
name = folder + "-example",
|
||||
srcs = native.glob(["src/main/java/org/wpilib/examples/" + folder + "/**/*.java"]),
|
||||
@@ -76,14 +76,25 @@ def build_commands():
|
||||
def build_snippets():
|
||||
_package_type("snippets")
|
||||
|
||||
for folder in SNIPPETS_FOLDERS:
|
||||
for folder in SNIPPET_FOLDERS:
|
||||
java_library(
|
||||
name = folder + "-snippet",
|
||||
srcs = native.glob(["src/main/java/org/wpilib/snippets/" + folder + "/**/*.java"]),
|
||||
deps = [
|
||||
"//apriltag:apriltag-java",
|
||||
"//cameraserver:cameraserver-java",
|
||||
"//cscore:cscore-java",
|
||||
"//hal:hal-java",
|
||||
"//wpilibj:wpilibj-java",
|
||||
"//ntcore:ntcore-java",
|
||||
"//wpimath:wpimath-java",
|
||||
"//wpilibj:wpilibj-java",
|
||||
"//commandsv2:commandsv2-java",
|
||||
"//wpiutil:wpiutil-java",
|
||||
"//romiVendordep:romiVendordep-java",
|
||||
"//xrpVendordep:xrpVendordep-java",
|
||||
"//wpiunits:wpiunits-java",
|
||||
"//epilogue-runtime:epilogue-java",
|
||||
"@bzlmodrio-opencv//libraries/java/opencv",
|
||||
],
|
||||
tags = ["wpi-example"],
|
||||
)
|
||||
@@ -91,7 +102,7 @@ def build_snippets():
|
||||
def build_templates():
|
||||
_package_type("templates")
|
||||
|
||||
for folder in TEMPLATES_FOLDERS:
|
||||
for folder in TEMPLATE_FOLDERS:
|
||||
java_library(
|
||||
name = folder + "-template",
|
||||
srcs = native.glob(["src/main/java/org/wpilib/templates/" + folder + "/**/*.java"]),
|
||||
@@ -107,7 +118,7 @@ def build_templates():
|
||||
)
|
||||
|
||||
def build_tests():
|
||||
for folder in TEST_FOLDERS:
|
||||
for folder in EXAMPLE_TESTS_FOLDERS:
|
||||
wpilib_java_junit5_test(
|
||||
name = folder + "-test",
|
||||
srcs = native.glob(["src/test/java/org/wpilib/examples/" + folder + "/**/*.java"]),
|
||||
@@ -122,3 +133,19 @@ def build_tests():
|
||||
],
|
||||
tags = ["wpi-example"],
|
||||
)
|
||||
|
||||
for folder in SNIPPET_TESTS_FOLDERS:
|
||||
wpilib_java_junit5_test(
|
||||
name = folder + "-test",
|
||||
srcs = native.glob(["src/test/java/org/wpilib/snippets/" + folder + "/**/*.java"]),
|
||||
deps = [
|
||||
":" + folder + "-snippet",
|
||||
"//hal:hal-java",
|
||||
"//ntcore:ntcore-java",
|
||||
"//wpilibj:wpilibj-java",
|
||||
"//commandsv2:commandsv2-java",
|
||||
"//wpimath:wpimath-java",
|
||||
"//wpiutil:wpiutil-java",
|
||||
],
|
||||
tags = ["wpi-example"],
|
||||
)
|
||||
|
||||
@@ -1,45 +1,27 @@
|
||||
EXAMPLES_FOLDERS = [
|
||||
"addressableled",
|
||||
"apriltagsvision",
|
||||
"arcadedrive",
|
||||
EXAMPLE_FOLDERS = [
|
||||
"arcadedrivegamepad",
|
||||
"armsimulation",
|
||||
"canpdp",
|
||||
"differentialdrivebot",
|
||||
"differentialdriveposeestimator",
|
||||
"digitalcommunication",
|
||||
"drivedistanceoffboard",
|
||||
"dutycycleencoder",
|
||||
"dutycycleinput",
|
||||
"elevatorexponentialprofile",
|
||||
"elevatorexponentialsimulation",
|
||||
"elevatorprofiledpid",
|
||||
"elevatorsimulation",
|
||||
"elevatortrapezoidprofile",
|
||||
"encoder",
|
||||
"eventloop",
|
||||
"flywheelbangbangcontroller",
|
||||
"gettingstarted",
|
||||
"gyro",
|
||||
"gyromecanum",
|
||||
"hatchbotinlined",
|
||||
"hatchbottraditional",
|
||||
"hidrumble",
|
||||
"httpcamera",
|
||||
"i2ccommunication",
|
||||
"intermediatevision",
|
||||
"mecanumbot",
|
||||
"mecanumdrive",
|
||||
"mecanumdriveposeestimator",
|
||||
"mechanism2d",
|
||||
"motorcontrol",
|
||||
"potentiometerpid",
|
||||
"quickvision",
|
||||
"rapidreactcommandbot",
|
||||
"romireference",
|
||||
"selectcommand",
|
||||
"simpledifferentialdrivesimulation",
|
||||
"solenoid",
|
||||
"statespacearm",
|
||||
"statespaceelevator",
|
||||
"statespaceflywheel",
|
||||
@@ -47,7 +29,6 @@ EXAMPLES_FOLDERS = [
|
||||
"swervebot",
|
||||
"swervedriveposeestimator",
|
||||
"sysidroutine",
|
||||
"tankdrive",
|
||||
"tankdrivegamepad",
|
||||
"unittest",
|
||||
"xrpreference",
|
||||
@@ -65,25 +46,39 @@ COMMANDS_V2_FOLDERS = [
|
||||
"subsystem2",
|
||||
]
|
||||
|
||||
SNIPPETS_FOLDERS = [
|
||||
SNIPPET_FOLDERS = [
|
||||
"accelerometercollision",
|
||||
"accelerometerfilter",
|
||||
"addressableled",
|
||||
"adxlaccelerometers",
|
||||
"analogaccelerometer",
|
||||
"analogencoder",
|
||||
"analoginput",
|
||||
"analogpotentiometer",
|
||||
"apriltagsvision",
|
||||
"canpdp",
|
||||
"digitalcommunication",
|
||||
"digitalinput",
|
||||
"dutycycleencoder",
|
||||
"dutycycleinput",
|
||||
"encoder",
|
||||
"encoderdrive",
|
||||
"encoderhoming",
|
||||
"eventloop",
|
||||
"flywheelbangbangcontroller",
|
||||
"httpcamera",
|
||||
"i2ccommunication",
|
||||
"intermediatevision",
|
||||
"limitswitch",
|
||||
"motorcontrol",
|
||||
"onboardimu",
|
||||
"profiledpidfeedforward",
|
||||
"quickvision",
|
||||
"selectcommand",
|
||||
"solenoid",
|
||||
]
|
||||
|
||||
TEMPLATES_FOLDERS = [
|
||||
TEMPLATE_FOLDERS = [
|
||||
"commandv2",
|
||||
"commandv2skeleton",
|
||||
"educational",
|
||||
@@ -101,11 +96,13 @@ TEMPLATES_FOLDERS = [
|
||||
"xrptimed",
|
||||
]
|
||||
|
||||
TEST_FOLDERS = [
|
||||
EXAMPLE_TESTS_FOLDERS = [
|
||||
"armsimulation",
|
||||
"digitalcommunication",
|
||||
"elevatorsimulation",
|
||||
"i2ccommunication",
|
||||
"potentiometerpid",
|
||||
"unittest",
|
||||
]
|
||||
|
||||
SNIPPET_TESTS_FOLDERS = [
|
||||
"digitalcommunication",
|
||||
"i2ccommunication",
|
||||
]
|
||||
|
||||
@@ -40,28 +40,36 @@ def main():
|
||||
snippets = load_foldernames(
|
||||
"wpilibjExamples/src/main/java/org/wpilib/snippets/snippets.json"
|
||||
)
|
||||
tests = load_tests(
|
||||
example_tests = load_tests(
|
||||
"wpilibjExamples/src/main/java/org/wpilib/examples/examples.json"
|
||||
)
|
||||
snippet_tests = load_tests(
|
||||
"wpilibjExamples/src/main/java/org/wpilib/snippets/snippets.json"
|
||||
)
|
||||
|
||||
output_file = "wpilibjExamples/example_projects.bzl"
|
||||
if len(sys.argv) == 2:
|
||||
output_file = sys.argv[1]
|
||||
|
||||
with open(output_file, "w") as f:
|
||||
f.write(
|
||||
'EXAMPLES_FOLDERS = [\n "' + '",\n "'.join(examples) + '",\n]\n\n'
|
||||
)
|
||||
f.write('EXAMPLE_FOLDERS = [\n "' + '",\n "'.join(examples) + '",\n]\n\n')
|
||||
f.write(
|
||||
'COMMANDS_V2_FOLDERS = [\n "' + '",\n "'.join(commands) + '",\n]\n\n'
|
||||
)
|
||||
f.write('SNIPPET_FOLDERS = [\n "' + '",\n "'.join(snippets) + '",\n]\n\n')
|
||||
f.write(
|
||||
'SNIPPETS_FOLDERS = [\n "' + '",\n "'.join(snippets) + '",\n]\n\n'
|
||||
'TEMPLATE_FOLDERS = [\n "' + '",\n "'.join(templates) + '",\n]\n\n'
|
||||
)
|
||||
f.write(
|
||||
'TEMPLATES_FOLDERS = [\n "' + '",\n "'.join(templates) + '",\n]\n\n'
|
||||
'EXAMPLE_TESTS_FOLDERS = [\n "'
|
||||
+ '",\n "'.join(example_tests)
|
||||
+ '",\n]\n\n'
|
||||
)
|
||||
f.write(
|
||||
'SNIPPET_TESTS_FOLDERS = [\n "'
|
||||
+ '",\n "'.join(snippet_tests)
|
||||
+ '",\n]\n'
|
||||
)
|
||||
f.write('TEST_FOLDERS = [\n "' + '",\n "'.join(tests) + '",\n]\n')
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
@@ -1,42 +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 org.wpilib.examples.arcadedrive;
|
||||
|
||||
import org.wpilib.drive.DifferentialDrive;
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.motor.PWMSparkMax;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with
|
||||
* arcade steering.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
|
||||
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
|
||||
private final DifferentialDrive m_robotDrive =
|
||||
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
|
||||
private final Joystick m_stick = new Joystick(0);
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
|
||||
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
|
||||
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightMotor.setInverted(true);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// Drive with arcade drive.
|
||||
// That means that the Y axis drives forward
|
||||
// and backward, and the X turns left and right.
|
||||
m_robotDrive.arcadeDrive(-m_stick.getY(), -m_stick.getX());
|
||||
}
|
||||
}
|
||||
@@ -10,71 +10,6 @@
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Tank Drive",
|
||||
"description": "Control a differential drive with twin-joystick tank drive in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "tankdrive",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Arcade Drive",
|
||||
"description": "Control a differential drivetrain with single-joystick arcade drive in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "arcadedrive",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Mecanum Drive",
|
||||
"description": "Control a mecanum drivetrain with a joystick in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Mecanum Drive",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "mecanumdrive",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "PDP CAN Monitoring",
|
||||
"description": "Monitor Power Distribution data such as voltage, current, temperature, etc.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"PDP",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "canpdp",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Solenoids",
|
||||
"description": "Control a single and double solenoid from joystick buttons.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "solenoid",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Encoder",
|
||||
"description": "View values from a quadrature encoder.",
|
||||
@@ -88,35 +23,6 @@
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "EventLoop",
|
||||
"description": "Manage a ball system using EventLoop and BooleanEvent.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Flywheel",
|
||||
"EventLoop"
|
||||
],
|
||||
"foldername": "eventloop",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Potentiometer PID",
|
||||
"description": "Maintain elevator position setpoints with a potentiometer and PID control.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Analog",
|
||||
"Elevator",
|
||||
"PID",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "potentiometerpid",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2,
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Elevator with trapezoid profiled PID",
|
||||
"description": "Reach elevator position setpoints with trapezoid profiles and smart motor controller PID.",
|
||||
@@ -169,7 +75,6 @@
|
||||
"Differential Drive",
|
||||
"PID",
|
||||
"Gyro",
|
||||
"Analog",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "gyro",
|
||||
@@ -178,28 +83,15 @@
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Gyro Mecanum",
|
||||
"name": "Mecanum Drive",
|
||||
"description": "Drive a mecanum drivetrain using field-oriented controls with a joystick.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Mecanum Drive",
|
||||
"Gyro",
|
||||
"Analog",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "gyromecanum",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "HID Rumble",
|
||||
"description": "Make human interface devices (HID) rumble.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "hidrumble",
|
||||
"foldername": "mecanumdrive",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
@@ -221,65 +113,6 @@
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Motor Control",
|
||||
"description": "Control a single motor with a joystick, displaying the movement of the motor using an encoder.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Encoder",
|
||||
"SmartDashboard",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "motorcontrol",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Simple Vision",
|
||||
"description": "Use the CameraServer class to stream from a USB Webcam without processing the images.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "quickvision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Intermediate Vision",
|
||||
"description": "Acquire images from an attached USB camera and add some annotation to the image (as you might do for showing operators the result of some image recognition) and send it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "intermediatevision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "HTTP Camera",
|
||||
"description": "Acquire images from an HTTP network camera and adds some annotation to the image (as you might do for showing operators the result of some image recognition), and sends it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "httpcamera",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "AprilTags Vision",
|
||||
"description": "On-roboRIO detection of AprilTags using an attached USB camera.",
|
||||
"tags": [
|
||||
"Vision",
|
||||
"AprilTags"
|
||||
],
|
||||
"foldername": "apriltagsvision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "'Traditional' Hatchbot",
|
||||
"description": "A fully-functional Commandv2 hatchbot for the 2019 game, written in the 'traditional' style, i.e. commands are given their own classes.",
|
||||
@@ -338,17 +171,6 @@
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Select Command Example",
|
||||
"description": "Use SelectCommand to select an autonomous routine.",
|
||||
"tags": [
|
||||
"Commandv2"
|
||||
],
|
||||
"foldername": "selectcommand",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "SwerveBot",
|
||||
"description": "Use kinematics and odometry with a swerve drive.",
|
||||
@@ -434,32 +256,6 @@
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Duty Cycle Input",
|
||||
"description": "View duty-cycle input.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Duty Cycle",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "dutycycleinput",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Addressable LED",
|
||||
"description": "Display a rainbow pattern on an addressable LED strip.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Basic Robot",
|
||||
"AddressableLEDs"
|
||||
],
|
||||
"foldername": "addressableled",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "DriveDistanceOffboard",
|
||||
"description": "Drive a differential drivetrain a set distance using TrapezoidProfile and smart motor controller PID.",
|
||||
@@ -722,45 +518,6 @@
|
||||
"xrp"
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Digital Communication Sample",
|
||||
"description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Digital Output"
|
||||
],
|
||||
"foldername": "digitalcommunication",
|
||||
"gradlebase": "java",
|
||||
"commandversion": 2,
|
||||
"robotclass": "Robot",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "I2C Communication Sample",
|
||||
"description": "Communicate with external devices (such as an Arduino) using the roboRIO's I2C port.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"I2C"
|
||||
],
|
||||
"foldername": "i2ccommunication",
|
||||
"gradlebase": "java",
|
||||
"commandversion": 2,
|
||||
"robotclass": "Robot",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Flywheel BangBangController",
|
||||
"description": "A sample program to demonstrate the use of a BangBangController with a flywheel to control RPM",
|
||||
"tags": [
|
||||
"Flywheel",
|
||||
"Simulation",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "flywheelbangbangcontroller",
|
||||
"gradlebase": "java",
|
||||
"commandversion": 2,
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "SysIdRoutine",
|
||||
"description": "A sample Commandv2 robot demonstrating use of the SysIdRoutine command factory",
|
||||
|
||||
@@ -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.
|
||||
|
||||
package org.wpilib.examples.gyromecanum;
|
||||
|
||||
import org.wpilib.drive.MecanumDrive;
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.imu.OnboardIMU;
|
||||
import org.wpilib.hardware.motor.PWMSparkMax;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors
|
||||
* in relation to the starting orientation of the robot (field-oriented controls).
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private static final int kFrontLeftChannel = 0;
|
||||
private static final int kRearLeftChannel = 1;
|
||||
private static final int kFrontRightChannel = 2;
|
||||
private static final int kRearRightChannel = 3;
|
||||
private static final OnboardIMU.MountOrientation kIMUMountOrientation =
|
||||
OnboardIMU.MountOrientation.kFlat;
|
||||
private static final int kJoystickPort = 0;
|
||||
|
||||
private final MecanumDrive m_robotDrive;
|
||||
private final OnboardIMU m_imu = new OnboardIMU(kIMUMountOrientation);
|
||||
private final Joystick m_joystick = new Joystick(kJoystickPort);
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
PWMSparkMax frontLeft = new PWMSparkMax(kFrontLeftChannel);
|
||||
PWMSparkMax rearLeft = new PWMSparkMax(kRearLeftChannel);
|
||||
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
|
||||
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
|
||||
|
||||
// Invert the right side motors.
|
||||
// You may need to change or remove this to match your robot.
|
||||
frontRight.setInverted(true);
|
||||
rearRight.setInverted(true);
|
||||
|
||||
m_robotDrive =
|
||||
new MecanumDrive(
|
||||
frontLeft::setDutyCycle,
|
||||
rearLeft::setDutyCycle,
|
||||
frontRight::setDutyCycle,
|
||||
rearRight::setDutyCycle);
|
||||
|
||||
SendableRegistry.addChild(m_robotDrive, frontLeft);
|
||||
SendableRegistry.addChild(m_robotDrive, rearLeft);
|
||||
SendableRegistry.addChild(m_robotDrive, frontRight);
|
||||
SendableRegistry.addChild(m_robotDrive, rearRight);
|
||||
}
|
||||
|
||||
/** Mecanum drive is used with the gyro angle as an input. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
m_robotDrive.driveCartesian(
|
||||
-m_joystick.getY(), -m_joystick.getX(), -m_joystick.getZ(), m_imu.getRotation2d());
|
||||
}
|
||||
}
|
||||
@@ -1,28 +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 org.wpilib.examples.hidrumble;
|
||||
|
||||
import org.wpilib.driverstation.Gamepad;
|
||||
import org.wpilib.driverstation.GenericHID.RumbleType;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
|
||||
/** This is a demo program showing the use of GenericHID's rumble feature. */
|
||||
public class Robot extends TimedRobot {
|
||||
private final Gamepad m_hid = new Gamepad(0);
|
||||
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
// Turn on rumble at the start of auto
|
||||
m_hid.setRumble(RumbleType.kLeftRumble, 1.0);
|
||||
m_hid.setRumble(RumbleType.kRightRumble, 1.0);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
// Stop the rumble when entering disabled
|
||||
m_hid.setRumble(RumbleType.kLeftRumble, 0.0);
|
||||
m_hid.setRumble(RumbleType.kRightRumble, 0.0);
|
||||
}
|
||||
}
|
||||
@@ -7,20 +7,26 @@ package org.wpilib.examples.mecanumdrive;
|
||||
import org.wpilib.drive.MecanumDrive;
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.imu.OnboardIMU;
|
||||
import org.wpilib.hardware.motor.PWMSparkMax;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
/** This is a demo program showing how to use Mecanum control with the MecanumDrive class. */
|
||||
/**
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors
|
||||
* in relation to the starting orientation of the robot (field-oriented controls).
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private static final int kFrontLeftChannel = 2;
|
||||
private static final int kRearLeftChannel = 3;
|
||||
private static final int kFrontRightChannel = 1;
|
||||
private static final int kRearRightChannel = 0;
|
||||
|
||||
private static final int kJoystickChannel = 0;
|
||||
private static final int kFrontLeftChannel = 0;
|
||||
private static final int kRearLeftChannel = 1;
|
||||
private static final int kFrontRightChannel = 2;
|
||||
private static final int kRearRightChannel = 3;
|
||||
private static final OnboardIMU.MountOrientation kIMUMountOrientation =
|
||||
OnboardIMU.MountOrientation.kFlat;
|
||||
private static final int kJoystickPort = 0;
|
||||
|
||||
private final MecanumDrive m_robotDrive;
|
||||
private final Joystick m_stick;
|
||||
private final OnboardIMU m_imu = new OnboardIMU(kIMUMountOrientation);
|
||||
private final Joystick m_joystick = new Joystick(kJoystickPort);
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
@@ -41,18 +47,18 @@ public class Robot extends TimedRobot {
|
||||
frontRight::setDutyCycle,
|
||||
rearRight::setDutyCycle);
|
||||
|
||||
m_stick = new Joystick(kJoystickChannel);
|
||||
|
||||
SendableRegistry.addChild(m_robotDrive, frontLeft);
|
||||
SendableRegistry.addChild(m_robotDrive, rearLeft);
|
||||
SendableRegistry.addChild(m_robotDrive, frontRight);
|
||||
SendableRegistry.addChild(m_robotDrive, rearRight);
|
||||
}
|
||||
|
||||
/** Mecanum drive is used with the gyro angle as an input. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// Use the joystick Y axis for forward movement, X axis for lateral
|
||||
// movement, and Z axis for rotation.
|
||||
m_robotDrive.driveCartesian(-m_stick.getY(), -m_stick.getX(), -m_stick.getZ());
|
||||
m_robotDrive.driveCartesian(
|
||||
-m_joystick.getY(), -m_joystick.getX(), -m_joystick.getZ(), m_imu.getRotation2d());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,79 +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 org.wpilib.examples.potentiometerpid;
|
||||
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.motor.PWMSparkMax;
|
||||
import org.wpilib.hardware.rotation.AnalogPotentiometer;
|
||||
import org.wpilib.math.controller.PIDController;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a soft potentiometer and a PID controller to
|
||||
* reach and maintain position setpoints on an elevator mechanism.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
static final int kPotChannel = 1;
|
||||
static final int kMotorChannel = 7;
|
||||
static final int kJoystickChannel = 3;
|
||||
|
||||
// The elevator can move 1.5 meters from top to bottom
|
||||
static final double kFullHeight = 1.5;
|
||||
|
||||
// Bottom, middle, and top elevator setpoints in meters
|
||||
static final double[] kSetpoints = {0.2, 0.8, 1.4};
|
||||
|
||||
// proportional, integral, and derivative velocity constants
|
||||
// DANGER: when tuning PID constants, high/inappropriate values for kP, kI,
|
||||
// and kD may cause dangerous, uncontrollable, or undesired behavior!
|
||||
private static final double kP = 0.7;
|
||||
private static final double kI = 0.35;
|
||||
private static final double kD = 0.25;
|
||||
|
||||
private final PIDController m_pidController = new PIDController(kP, kI, kD);
|
||||
// Scaling is handled internally
|
||||
private final AnalogPotentiometer m_potentiometer =
|
||||
new AnalogPotentiometer(kPotChannel, kFullHeight);
|
||||
private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(kMotorChannel);
|
||||
private final Joystick m_joystick = new Joystick(kJoystickChannel);
|
||||
|
||||
private int m_index;
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
// Move to the bottom setpoint when teleop starts
|
||||
m_index = 0;
|
||||
m_pidController.setSetpoint(kSetpoints[m_index]);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// Read from the sensor
|
||||
double position = m_potentiometer.get();
|
||||
|
||||
// Run the PID Controller
|
||||
double pidOut = m_pidController.calculate(position);
|
||||
|
||||
// Apply PID output
|
||||
m_elevatorMotor.setDutyCycle(pidOut);
|
||||
|
||||
// when the button is pressed once, the selected elevator setpoint is incremented
|
||||
if (m_joystick.getTriggerPressed()) {
|
||||
// index of the elevator setpoint wraps around.
|
||||
m_index = (m_index + 1) % kSetpoints.length;
|
||||
System.out.println("m_index = " + m_index);
|
||||
m_pidController.setSetpoint(kSetpoints[m_index]);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
m_elevatorMotor.close();
|
||||
m_potentiometer.close();
|
||||
m_pidController.close();
|
||||
m_index = 0;
|
||||
super.close();
|
||||
}
|
||||
}
|
||||
@@ -1,44 +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 org.wpilib.examples.tankdrive;
|
||||
|
||||
import org.wpilib.drive.DifferentialDrive;
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.motor.PWMSparkMax;
|
||||
import org.wpilib.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class, specifically it contains
|
||||
* the code necessary to operate a robot with tank drive.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final DifferentialDrive m_robotDrive;
|
||||
private final Joystick m_leftStick;
|
||||
private final Joystick m_rightStick;
|
||||
|
||||
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
|
||||
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightMotor.setInverted(true);
|
||||
|
||||
m_robotDrive = new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
|
||||
m_leftStick = new Joystick(0);
|
||||
m_rightStick = new Joystick(1);
|
||||
|
||||
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
|
||||
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
m_robotDrive.tankDrive(-m_leftStick.getY(), -m_rightStick.getY());
|
||||
}
|
||||
}
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.addressableled;
|
||||
package org.wpilib.snippets.addressableled;
|
||||
|
||||
import static org.wpilib.units.Units.Meters;
|
||||
import static org.wpilib.units.Units.MetersPerSecond;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.apriltagsvision;
|
||||
package org.wpilib.snippets.apriltagsvision;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import org.opencv.core.Mat;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.canpdp;
|
||||
package org.wpilib.snippets.canpdp;
|
||||
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.power.PowerDistribution;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.digitalcommunication;
|
||||
package org.wpilib.snippets.digitalcommunication;
|
||||
|
||||
import java.util.Optional;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.dutycycleinput;
|
||||
package org.wpilib.snippets.dutycycleinput;
|
||||
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.hardware.rotation.DutyCycle;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.eventloop;
|
||||
package org.wpilib.snippets.eventloop;
|
||||
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.event.BooleanEvent;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.flywheelbangbangcontroller;
|
||||
package org.wpilib.snippets.flywheelbangbangcontroller;
|
||||
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.httpcamera;
|
||||
package org.wpilib.snippets.httpcamera;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Point;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.i2ccommunication;
|
||||
package org.wpilib.snippets.i2ccommunication;
|
||||
|
||||
import java.util.Optional;
|
||||
import org.wpilib.driverstation.DriverStation;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.intermediatevision;
|
||||
package org.wpilib.snippets.intermediatevision;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Point;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.motorcontrol;
|
||||
package org.wpilib.snippets.motorcontrol;
|
||||
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.quickvision;
|
||||
package org.wpilib.snippets.quickvision;
|
||||
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
import org.wpilib.vision.stream.CameraServer;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.selectcommand;
|
||||
package org.wpilib.snippets.selectcommand;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.selectcommand;
|
||||
package org.wpilib.snippets.selectcommand;
|
||||
|
||||
import org.wpilib.command2.Command;
|
||||
import org.wpilib.command2.CommandScheduler;
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.selectcommand;
|
||||
package org.wpilib.snippets.selectcommand;
|
||||
|
||||
import java.util.Map;
|
||||
import org.wpilib.command2.Command;
|
||||
@@ -171,5 +171,166 @@
|
||||
"foldername": "profiledpidfeedforward",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Addressable LED",
|
||||
"description": "Display a rainbow pattern on an addressable LED strip.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Basic Robot",
|
||||
"AddressableLEDs"
|
||||
],
|
||||
"foldername": "addressableled",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "AprilTags Vision",
|
||||
"description": "On-roboRIO detection of AprilTags using an attached USB camera.",
|
||||
"tags": [
|
||||
"Vision",
|
||||
"AprilTags"
|
||||
],
|
||||
"foldername": "apriltagsvision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "PDP CAN Monitoring",
|
||||
"description": "Monitor Power Distribution data such as voltage, current, temperature, etc.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"PDP",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "canpdp",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Digital Communication Sample",
|
||||
"description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Digital Output"
|
||||
],
|
||||
"foldername": "digitalcommunication",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Duty Cycle Input",
|
||||
"description": "View duty-cycle input.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Duty Cycle",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "dutycycleinput",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "EventLoop",
|
||||
"description": "Manage a ball system using EventLoop and BooleanEvent.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Flywheel",
|
||||
"EventLoop"
|
||||
],
|
||||
"foldername": "eventloop",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Flywheel BangBangController",
|
||||
"description": "A sample program to demonstrate the use of a BangBangController with a flywheel to control RPM",
|
||||
"tags": [
|
||||
"Flywheel",
|
||||
"Simulation",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "flywheelbangbangcontroller",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "HTTP Camera",
|
||||
"description": "Acquire images from an HTTP network camera and adds some annotation to the image (as you might do for showing operators the result of some image recognition), and sends it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "httpcamera",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "I2C Communication Sample",
|
||||
"description": "Communicate with external devices (such as an Arduino) using the roboRIO's I2C port.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"I2C"
|
||||
],
|
||||
"foldername": "i2ccommunication",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"hasunittests": true
|
||||
},
|
||||
{
|
||||
"name": "Intermediate Vision",
|
||||
"description": "Acquire images from an attached USB camera and add some annotation to the image (as you might do for showing operators the result of some image recognition) and send it to the dashboard for display.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "intermediatevision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Motor Control",
|
||||
"description": "Control a single motor with a joystick, displaying the movement of the motor using an encoder.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Encoder",
|
||||
"SmartDashboard",
|
||||
"Joystick"
|
||||
],
|
||||
"foldername": "motorcontrol",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Select Command Example",
|
||||
"description": "Use SelectCommand to select an autonomous routine.",
|
||||
"tags": [
|
||||
"Commandv2"
|
||||
],
|
||||
"foldername": "selectcommand",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Simple Vision",
|
||||
"description": "Use the CameraServer class to stream from a USB Webcam without processing the images.",
|
||||
"tags": [
|
||||
"Vision"
|
||||
],
|
||||
"foldername": "quickvision",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
},
|
||||
{
|
||||
"name": "Solenoids",
|
||||
"description": "Control a single and double solenoid from joystick buttons.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "solenoid",
|
||||
"gradlebase": "java",
|
||||
"robotclass": "Robot"
|
||||
}
|
||||
]
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.solenoid;
|
||||
package org.wpilib.snippets.solenoid;
|
||||
|
||||
import org.wpilib.driverstation.Joystick;
|
||||
import org.wpilib.framework.TimedRobot;
|
||||
@@ -1,173 +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 org.wpilib.examples.potentiometerpid;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.api.parallel.ResourceLock;
|
||||
import org.wpilib.hardware.hal.HAL;
|
||||
import org.wpilib.hardware.hal.HAL.SimPeriodicBeforeCallback;
|
||||
import org.wpilib.hardware.hal.RobotMode;
|
||||
import org.wpilib.math.system.DCMotor;
|
||||
import org.wpilib.math.util.Units;
|
||||
import org.wpilib.simulation.AnalogInputSim;
|
||||
import org.wpilib.simulation.DriverStationSim;
|
||||
import org.wpilib.simulation.ElevatorSim;
|
||||
import org.wpilib.simulation.JoystickSim;
|
||||
import org.wpilib.simulation.PWMMotorControllerSim;
|
||||
import org.wpilib.simulation.SimHooks;
|
||||
import org.wpilib.system.RobotController;
|
||||
|
||||
@ResourceLock("timing")
|
||||
class PotentiometerPIDTest {
|
||||
private final DCMotor m_elevatorGearbox = DCMotor.getVex775Pro(4);
|
||||
private static final double kElevatorGearing = 10.0;
|
||||
private static final double kElevatorDrumRadius = Units.inchesToMeters(2.0);
|
||||
private static final double kCarriageMassKg = 4.0; // kg
|
||||
|
||||
private Robot m_robot;
|
||||
private Thread m_thread;
|
||||
|
||||
private ElevatorSim m_elevatorSim;
|
||||
private PWMMotorControllerSim m_motorSim;
|
||||
private AnalogInputSim m_analogSim;
|
||||
private SimPeriodicBeforeCallback m_callback;
|
||||
private JoystickSim m_joystickSim;
|
||||
|
||||
@BeforeEach
|
||||
void startThread() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
SimHooks.setProgramStarted(false);
|
||||
DriverStationSim.resetData();
|
||||
m_robot = new Robot();
|
||||
m_thread = new Thread(m_robot::startCompetition);
|
||||
m_elevatorSim =
|
||||
new ElevatorSim(
|
||||
m_elevatorGearbox,
|
||||
kElevatorGearing,
|
||||
kCarriageMassKg,
|
||||
kElevatorDrumRadius,
|
||||
0.0,
|
||||
Robot.kFullHeight,
|
||||
true,
|
||||
0);
|
||||
m_analogSim = new AnalogInputSim(Robot.kPotChannel);
|
||||
m_motorSim = new PWMMotorControllerSim(Robot.kMotorChannel);
|
||||
m_joystickSim = new JoystickSim(Robot.kJoystickChannel);
|
||||
|
||||
m_callback =
|
||||
HAL.registerSimPeriodicBeforeCallback(
|
||||
() -> {
|
||||
m_elevatorSim.setInputVoltage(
|
||||
m_motorSim.getDutyCycle() * RobotController.getBatteryVoltage());
|
||||
m_elevatorSim.update(0.02);
|
||||
|
||||
/*
|
||||
meters = (v / 3.3v) * range
|
||||
meters / range = v / 3.3v
|
||||
3.3v * (meters / range) = v
|
||||
*/
|
||||
m_analogSim.setVoltage(
|
||||
RobotController.getVoltage3V3()
|
||||
* (m_elevatorSim.getPosition() / Robot.kFullHeight));
|
||||
});
|
||||
|
||||
m_thread.start();
|
||||
SimHooks.waitForProgramStart();
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void stopThread() {
|
||||
m_robot.endCompetition();
|
||||
try {
|
||||
m_thread.interrupt();
|
||||
m_thread.join();
|
||||
} catch (InterruptedException ex) {
|
||||
Thread.currentThread().interrupt();
|
||||
}
|
||||
m_robot.close();
|
||||
m_callback.close();
|
||||
m_analogSim.resetData();
|
||||
}
|
||||
|
||||
@Test
|
||||
void teleopTest() {
|
||||
// teleop init
|
||||
{
|
||||
DriverStationSim.setRobotMode(RobotMode.TELEOPERATED);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
|
||||
assertTrue(m_analogSim.getInitialized());
|
||||
}
|
||||
|
||||
// first setpoint
|
||||
{
|
||||
// advance 50 timesteps
|
||||
SimHooks.stepTiming(1);
|
||||
|
||||
assertEquals(Robot.kSetpoints[0], m_elevatorSim.getPosition(), 0.1);
|
||||
}
|
||||
|
||||
// second setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.setTrigger(true);
|
||||
m_joystickSim.notifyNewData();
|
||||
|
||||
// advance 50 timesteps
|
||||
SimHooks.stepTiming(1);
|
||||
|
||||
assertEquals(Robot.kSetpoints[1], m_elevatorSim.getPosition(), 0.1);
|
||||
}
|
||||
|
||||
// we need to unpress the button
|
||||
{
|
||||
m_joystickSim.setTrigger(false);
|
||||
m_joystickSim.notifyNewData();
|
||||
|
||||
// advance 10 timesteps
|
||||
SimHooks.stepTiming(0.2);
|
||||
}
|
||||
|
||||
// third setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.setTrigger(true);
|
||||
m_joystickSim.notifyNewData();
|
||||
|
||||
// advance 50 timesteps
|
||||
SimHooks.stepTiming(1);
|
||||
|
||||
assertEquals(Robot.kSetpoints[2], m_elevatorSim.getPosition(), 0.1);
|
||||
}
|
||||
|
||||
// we need to unpress the button
|
||||
{
|
||||
m_joystickSim.setTrigger(false);
|
||||
m_joystickSim.notifyNewData();
|
||||
|
||||
// advance 10 timesteps
|
||||
SimHooks.stepTiming(0.2);
|
||||
}
|
||||
|
||||
// rollover: first setpoint
|
||||
{
|
||||
// press button to advance setpoint
|
||||
m_joystickSim.setTrigger(true);
|
||||
m_joystickSim.notifyNewData();
|
||||
|
||||
// advance 60 timesteps
|
||||
SimHooks.stepTiming(1.2);
|
||||
|
||||
assertEquals(Robot.kSetpoints[0], m_elevatorSim.getPosition(), 0.1);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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 org.wpilib.examples.digitalcommunication;
|
||||
package org.wpilib.snippets.digitalcommunication;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
@@ -2,12 +2,13 @@
|
||||
// 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 org.wpilib.examples.i2ccommunication;
|
||||
package org.wpilib.snippets.i2ccommunication;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTimeoutPreemptively;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.nio.charset.StandardCharsets;
|
||||
import java.time.Duration;
|
||||
import java.util.concurrent.CompletableFuture;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
@@ -42,7 +43,8 @@ class I2CCommunicationTest {
|
||||
m_future = new CompletableFuture<>();
|
||||
m_callback =
|
||||
m_i2c.registerWriteCallback(
|
||||
(name, buffer, count) -> m_future.complete(new String(buffer, 0, count)));
|
||||
(name, buffer, count) ->
|
||||
m_future.complete(new String(buffer, 0, count, StandardCharsets.UTF_8)));
|
||||
m_robot = new Robot();
|
||||
m_thread = new Thread(m_robot::startCompetition);
|
||||
m_thread.start();
|
||||
Reference in New Issue
Block a user