Skip to content

Commit fe6167d

Browse files
author
NewtonCrosby
committed
Updated implementation to use overload typing constructors and tests to verify proper instantiation and functionality.
1 parent 849ba52 commit fe6167d

File tree

2 files changed

+400
-18
lines changed

2 files changed

+400
-18
lines changed

commands2/ramsetecommand.py

Lines changed: 89 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
# the WPILib BSD license file in the root directory of this project.
44
from __future__ import annotations
55

6-
from typing import Callable, Union, Optional
6+
from typing import Callable, Union, Optional, Tuple, overload
77
from wpimath.controller import (
88
PIDController,
99
RamseteController,
@@ -16,6 +16,7 @@
1616
DifferentialDriveWheelSpeeds,
1717
)
1818
from wpimath.trajectory import Trajectory
19+
from wpimath import units as units
1920
from wpiutil import SendableBuilder
2021
from wpilib import Timer
2122

@@ -36,18 +37,35 @@ class RamseteCommand(Command):
3637
Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID
3738
functionality of a "smart" motor controller) may use the secondary constructor that omits the PID
3839
and feedforward functionality, returning only the raw wheel speeds from the RAMSETE controller.
39-
40-
This class is provided by the NewCommands VendorDep
4140
"""
4241

42+
@overload
43+
def __init__(
44+
self,
45+
trajectory: Trajectory,
46+
pose: Callable[[], Pose2d],
47+
controller: RamseteController,
48+
kinematics: DifferentialDriveKinematics,
49+
requirements: Tuple[Subsystem],
50+
*,
51+
outputMPS: Optional[
52+
Callable[[units.meters_per_second, units.meters_per_second], None]
53+
],
54+
):
55+
...
56+
4357
def __init__(
4458
self,
4559
trajectory: Trajectory,
4660
pose: Callable[[], Pose2d],
4761
controller: RamseteController,
4862
kinematics: DifferentialDriveKinematics,
49-
outputVolts: Callable[[float, float], None],
50-
*requirements: Subsystem,
63+
requirements: Tuple[Subsystem],
64+
*,
65+
outputVolts: Optional[Callable[[units.volts, units.volts], None]] = None,
66+
outputMPS: Optional[
67+
Callable[[units.meters_per_second, units.meters_per_second], None]
68+
] = None,
5169
feedforward: Optional[SimpleMotorFeedforwardMeters] = None,
5270
leftController: Optional[PIDController] = None,
5371
rightController: Optional[PIDController] = None,
@@ -65,10 +83,39 @@ def __init__(
6583
provide this.
6684
:param controller: The RAMSETE controller used to follow the trajectory.
6785
:param kinematics: The kinematics for the robot drivetrain.
68-
:param outputVolts: A function that consumes the computed left and right outputs (in volts) for
69-
the robot drive.
7086
:param requirements: The subsystems to require.
7187
88+
REQUIRED KEYWORD PARAMETERS
89+
Note: The output mode must be specified by the users of RamseteCommands. Users can specify ONE of
90+
an output function that will supply the consumer with left and right speeds in `units.meters_per_second`
91+
or in `units.volts`. If neither, or both, are supplied to the constructor a `RuntimeError` will be
92+
raised.
93+
:param outputVolts A function that consumes the computed left and right outputs in `units.volts`
94+
:param outputMPS A function that consumes the computed left and right outputs in `units.meters_per_second`
95+
96+
97+
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. PID
98+
control and feedforward are handled internally, and outputs are scaled -12 to 12 representing
99+
units of volts.
100+
101+
Note: The controller will *not* set the outputVolts to zero upon completion of the path -
102+
this is left to the user, since it is not appropriate for paths with nonstationary endstates.
103+
104+
:param trajectory: The trajectory to follow.
105+
:param pose: A function that supplies the robot pose - use one of the odometry classes to
106+
provide this.
107+
:param controller: The RAMSETE controller used to follow the trajectory.
108+
:param kinematics: The kinematics for the robot drivetrain.
109+
:param requirements: The subsystems to require.
110+
111+
REQUIRED KEYWORD PARAMETERS
112+
Note: The output mode must be specified by the users of RamseteCommands. Users can specify ONE of
113+
an output function that will supply the consumer with left and right speeds in `units.meters_per_second`
114+
or in `units.volts`. If neither, or both, are supplied to the constructor a `RuntimeError` will be
115+
raised.
116+
:param outputVolts A function that consumes the computed left and right outputs in `units.volts`
117+
:param outputMPS A function that consumes the computed left and right outputs in `units.meters_per_second`
118+
72119
OPTIONAL PARAMETERS
73120
When the following optional parameters are provided, when executed, the RamseteCommand will follow
74121
provided trajectory. PID control and feedforward are handled internally, and the outputs are scaled
@@ -89,12 +136,38 @@ def __init__(
89136
self.pose = pose
90137
self.follower = controller
91138
self.kinematics = kinematics
92-
self.output = outputVolts
93-
self.usePID = False
139+
140+
# Required requirements check for output
141+
if outputMPS is None and outputVolts is None:
142+
raise RuntimeError(
143+
f"Failed to instantiate RamseteCommand, no output consumer provided. Must provide either output in meters per second or volts."
144+
)
145+
146+
if outputMPS is not None and outputVolts is not None:
147+
raise RuntimeError(
148+
f"Failed to instantiate RamseteCommand, too many consumers provided. Must provide either output in meters per second or volts but not both."
149+
)
150+
151+
# If the above check fails, then one of them is not None. Take the one supplied and assign it for output.
152+
if outputMPS is not None:
153+
self.output = outputMPS
154+
else:
155+
self.output = outputVolts
156+
94157
# Optional requirements checks. If any one of the optional parameters are not None, then all the optional
95158
# requirements become required.
96-
if feedforward or leftController or rightController or wheelSpeeds is not None:
97-
if feedforward or leftController or rightController or wheelSpeeds is None:
159+
if (
160+
feedforward is not None
161+
or leftController is not None
162+
or rightController is not None
163+
or wheelSpeeds is not None
164+
):
165+
if (
166+
feedforward is None
167+
or leftController is None
168+
or rightController is None
169+
or wheelSpeeds is None
170+
):
98171
raise RuntimeError(
99172
f"Failed to instantiate RamseteCommand, not all optional arguments were provided.\n \
100173
Feedforward - {feedforward}, LeftController - {leftController}, RightController - {rightController}, WheelSpeeds - {wheelSpeeds} "
@@ -105,10 +178,12 @@ def __init__(
105178
self.wheelspeeds = wheelSpeeds
106179
self.feedforward = feedforward
107180
self.usePID = True
181+
else:
182+
self.usePID = False
108183
self._prevSpeeds = DifferentialDriveWheelSpeeds()
109184
self._prevTime = -1.0
110185

111-
self.addRequirements(*requirements)
186+
self.addRequirements(requirements)
112187

113188
def initialize(self):
114189
self._prevTime = -1
@@ -158,11 +233,12 @@ def execute(self):
158233
rightOutput = rightFeedforward + self.rightController.calculate(
159234
self.wheelspeeds().right, rightSpeedSetpoint
160235
)
236+
self.output(leftOutput, rightOutput)
161237
else:
162238
leftOutput = leftSpeedSetpoint
163239
rightOutput = rightSpeedSetpoint
240+
self.output(leftOutput, rightOutput)
164241

165-
self.output(leftOutput, rightOutput)
166242
self._prevSpeeds = targetWheelSpeeds
167243
self._prevTime = curTime
168244

0 commit comments

Comments
 (0)