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",
|
||||
|
||||
Reference in New Issue
Block a user