mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[robotpy][examples] Split examples and snippets (#8944)
This also updates the bazel scripts to behave more like the C++ and Java examples, and updates the copybara scripts to be able to sync up `mostrobotpy`
This commit is contained in:
33
robotpyExamples/examples/ArmSimulation/constants.py
Normal file
33
robotpyExamples/examples/ArmSimulation/constants.py
Normal file
@@ -0,0 +1,33 @@
|
||||
#
|
||||
# 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 math
|
||||
|
||||
from wpimath import units
|
||||
|
||||
|
||||
class Constants:
|
||||
kMotorPort = 0
|
||||
kEncoderAChannel = 0
|
||||
kEncoderBChannel = 1
|
||||
kJoystickPort = 0
|
||||
|
||||
kArmPositionKey = "ArmPosition"
|
||||
kArmPKey = "ArmP"
|
||||
|
||||
# The P gain for the PID controller that drives this arm.
|
||||
kDefaultArmKp = 50.0
|
||||
kDefaultArmSetpointDegrees = 75.0
|
||||
|
||||
# distance per pulse = (angle per revolution) / (pulses per revolution)
|
||||
# = (2 * PI rads) / (4096 pulses)
|
||||
kArmEncoderDistPerPulse = 2.0 * math.pi / 4096
|
||||
|
||||
kArmReduction = 200
|
||||
kArmMass = 8.0 # Kilograms
|
||||
kArmLength = units.inchesToMeters(30)
|
||||
kMinAngleRads = units.degreesToRadians(-75)
|
||||
kMaxAngleRads = units.degreesToRadians(255)
|
||||
38
robotpyExamples/examples/ArmSimulation/robot.py
Executable file
38
robotpyExamples/examples/ArmSimulation/robot.py
Executable file
@@ -0,0 +1,38 @@
|
||||
#!/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
|
||||
|
||||
from constants import Constants
|
||||
from subsystems.arm import Arm
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""This is a sample program to demonstrate the use of arm simulation with existing code."""
|
||||
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
self.arm = Arm()
|
||||
self.joystick = wpilib.Joystick(Constants.kJoystickPort)
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
self.arm.simulationPeriodic()
|
||||
|
||||
def teleopInit(self) -> None:
|
||||
self.arm.loadPreferences()
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
if self.joystick.getTrigger():
|
||||
# Here, we run PID control like normal.
|
||||
self.arm.reachSetpoint()
|
||||
else:
|
||||
# Otherwise, we disable the motor.
|
||||
self.arm.stop()
|
||||
|
||||
def disabledInit(self) -> None:
|
||||
# This just makes sure that our simulation code knows that the motor's off.
|
||||
self.arm.stop()
|
||||
114
robotpyExamples/examples/ArmSimulation/subsystems/arm.py
Normal file
114
robotpyExamples/examples/ArmSimulation/subsystems/arm.py
Normal file
@@ -0,0 +1,114 @@
|
||||
#
|
||||
# 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 wpilib.simulation
|
||||
import wpimath
|
||||
import wpimath.units
|
||||
import wpiutil
|
||||
|
||||
from constants import Constants
|
||||
|
||||
|
||||
class Arm:
|
||||
def __init__(self) -> None:
|
||||
# The P gain for the PID controller that drives this arm.
|
||||
self.armKp = Constants.kDefaultArmKp
|
||||
self.armSetpointDegrees = Constants.kDefaultArmSetpointDegrees
|
||||
|
||||
# The arm gearbox represents a gearbox containing two Vex 775pro motors.
|
||||
self.armGearbox = wpimath.DCMotor.vex775Pro(2)
|
||||
|
||||
# Standard classes for controlling our arm
|
||||
self.controller = wpimath.PIDController(self.armKp, 0, 0)
|
||||
self.encoder = wpilib.Encoder(
|
||||
Constants.kEncoderAChannel, Constants.kEncoderBChannel
|
||||
)
|
||||
self.motor = wpilib.PWMSparkMax(Constants.kMotorPort)
|
||||
|
||||
# Simulation classes help us simulate what's going on, including gravity.
|
||||
# This arm sim represents an arm that can travel from -75 degrees (rotated down front)
|
||||
# to 255 degrees (rotated down in the back).
|
||||
self.armSim = wpilib.simulation.SingleJointedArmSim(
|
||||
self.armGearbox,
|
||||
Constants.kArmReduction,
|
||||
wpilib.simulation.SingleJointedArmSim.estimateMOI(
|
||||
Constants.kArmLength, Constants.kArmMass
|
||||
),
|
||||
Constants.kArmLength,
|
||||
Constants.kMinAngleRads,
|
||||
Constants.kMaxAngleRads,
|
||||
True,
|
||||
0,
|
||||
[Constants.kArmEncoderDistPerPulse, 0.0],
|
||||
)
|
||||
self.encoderSim = wpilib.simulation.EncoderSim(self.encoder)
|
||||
|
||||
# Create a Mechanism2d display of an Arm with a fixed ArmTower and moving Arm.
|
||||
self.mech2d = wpilib.Mechanism2d(60, 60)
|
||||
self.armPivot = self.mech2d.getRoot("ArmPivot", 30, 30)
|
||||
self.armTower = self.armPivot.appendLigament("ArmTower", 30, -90)
|
||||
self.armLigament = self.armPivot.appendLigament(
|
||||
"Arm",
|
||||
30,
|
||||
wpimath.units.radiansToDegrees(self.armSim.getAngle()),
|
||||
6,
|
||||
wpiutil.Color8Bit(wpiutil.Color.YELLOW),
|
||||
)
|
||||
|
||||
# Subsystem constructor.
|
||||
self.encoder.setDistancePerPulse(Constants.kArmEncoderDistPerPulse)
|
||||
|
||||
# Put Mechanism 2d to SmartDashboard
|
||||
wpilib.SmartDashboard.putData("Arm Sim", self.mech2d)
|
||||
self.armTower.setColor(wpiutil.Color8Bit(wpiutil.Color.BLUE))
|
||||
|
||||
# Set the Arm position setpoint and P constant to Preferences if the keys don't already exist
|
||||
wpilib.Preferences.initDouble(
|
||||
Constants.kArmPositionKey, self.armSetpointDegrees
|
||||
)
|
||||
wpilib.Preferences.initDouble(Constants.kArmPKey, self.armKp)
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
# In this method, we update our simulation of what our arm is doing
|
||||
# First, we set our "inputs" (voltages)
|
||||
self.armSim.setInput(
|
||||
[self.motor.getThrottle() * wpilib.RobotController.getBatteryVoltage()]
|
||||
)
|
||||
|
||||
# Next, we update it. The standard loop time is 20ms.
|
||||
self.armSim.update(0.020)
|
||||
|
||||
# Finally, we set our simulated encoder's readings and simulated battery voltage
|
||||
self.encoderSim.setDistance(self.armSim.getAngle())
|
||||
# SimBattery estimates loaded battery voltages
|
||||
wpilib.simulation.RoboRioSim.setVInVoltage(
|
||||
wpilib.simulation.BatterySim.calculate([self.armSim.getCurrentDraw()])
|
||||
)
|
||||
|
||||
# Update the Mechanism Arm angle based on the simulated arm angle
|
||||
self.armLigament.setAngle(
|
||||
wpimath.units.radiansToDegrees(self.armSim.getAngle())
|
||||
)
|
||||
|
||||
def loadPreferences(self) -> None:
|
||||
# Read Preferences for Arm setpoint and kP on entering Teleop
|
||||
self.armSetpointDegrees = wpilib.Preferences.getDouble(
|
||||
Constants.kArmPositionKey, self.armSetpointDegrees
|
||||
)
|
||||
if self.armKp != wpilib.Preferences.getDouble(Constants.kArmPKey, self.armKp):
|
||||
self.armKp = wpilib.Preferences.getDouble(Constants.kArmPKey, self.armKp)
|
||||
self.controller.setP(self.armKp)
|
||||
|
||||
def reachSetpoint(self) -> None:
|
||||
pidOutput = self.controller.calculate(
|
||||
self.encoder.getDistance(),
|
||||
wpimath.units.degreesToRadians(self.armSetpointDegrees),
|
||||
)
|
||||
self.motor.setVoltage(pidOutput)
|
||||
|
||||
def stop(self) -> None:
|
||||
self.motor.setThrottle(0.0)
|
||||
Reference in New Issue
Block a user