-
Notifications
You must be signed in to change notification settings - Fork 18
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Adds MecanumControllerCommand to Commands2. #35
Open
lospugs
wants to merge
3
commits into
robotpy:main
Choose a base branch
from
lospugs:mecanumcontrollercommand
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from all commits
Commits
Show all changes
3 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,216 @@ | ||
# 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. | ||
from __future__ import annotations | ||
from typing import Set, Callable, Union, List, Optional | ||
|
||
from wpimath.controller import ( | ||
HolonomicDriveController, | ||
PIDController, | ||
ProfiledPIDControllerRadians, | ||
SimpleMotorFeedforwardMeters, | ||
) | ||
from wpimath.geometry import Pose2d, Rotation2d | ||
from wpimath.kinematics import ( | ||
ChassisSpeeds, | ||
MecanumDriveKinematics, | ||
MecanumDriveWheelSpeeds, | ||
) | ||
from wpimath.trajectory import Trajectory | ||
from wpilib import Timer | ||
|
||
from .subsystem import Subsystem | ||
from .command import Command | ||
|
||
|
||
class MecanumControllerCommand(Command): | ||
""" | ||
A command that uses two PID controllers (PIDController) and a ProfiledPIDController | ||
(ProfiledPIDController) to follow a trajectory Trajectory with a mecanum drive. | ||
|
||
The command handles trajectory-following, Velocity PID calculations, and feedforwards | ||
internally. This is intended to be a more-or-less "complete solution" that can be used by teams | ||
without a great deal of controls expertise. | ||
|
||
Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID | ||
functionality of a "smart" motor controller) may use the secondary constructor that omits the PID | ||
and feedforward functionality, returning only the raw wheel speeds from the PID controllers. | ||
|
||
The robot angle controller does not follow the angle given by the trajectory but rather goes | ||
to the angle given in the final state of the trajectory. | ||
""" | ||
|
||
def __init__( | ||
self, | ||
trajectory: Trajectory, | ||
pose: Callable[[], Pose2d], | ||
kinematics: MecanumDriveKinematics, | ||
xController: PIDController, | ||
yController: PIDController, | ||
thetaController: ProfiledPIDControllerRadians, | ||
# rotationSupplier: Callable[[], Rotation2d], | ||
maxWheelVelocityMetersPerSecond: float, | ||
outputConsumer: Callable[[MecanumDriveWheelSpeeds], None], | ||
*requirements: Subsystem, | ||
feedforward: Optional[SimpleMotorFeedforwardMeters] = None, | ||
frontLeftController: Optional[PIDController] = None, | ||
rearLeftController: Optional[PIDController] = None, | ||
frontRightController: Optional[PIDController] = None, | ||
rearRightController: Optional[PIDController] = None, | ||
currentWheelSpeedsSupplier: Optional[ | ||
Callable[[], MecanumDriveWheelSpeeds] | ||
] = None, | ||
): | ||
super().__init__() | ||
|
||
self._trajectory: Trajectory = trajectory | ||
self._pose = pose | ||
self._kinematics = kinematics | ||
self._controller = HolonomicDriveController( | ||
xController, yController, thetaController | ||
) | ||
# self.rotationSupplier = rotationSupplier | ||
self._maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond | ||
self._outputConsumer = outputConsumer | ||
|
||
# Member to track time of last loop execution | ||
self._prevTime = 0 | ||
self._usePID = False | ||
|
||
# Optional requirements checks. If any one of the feedforward, pidcontrollers, or wheelspeedsuppliers | ||
# are not None, then all should be non-null. Raise RuntimeError if they are. The List of PID controllers | ||
# should be equal to each corner of the robot being commanded. | ||
if ( | ||
feedforward | ||
or frontLeftController | ||
or rearLeftController | ||
or frontRightController | ||
or rearRightController | ||
or currentWheelSpeedsSupplier is not None | ||
): | ||
if ( | ||
feedforward | ||
or frontLeftController | ||
or rearLeftController | ||
or frontRightController | ||
or rearRightController | ||
or currentWheelSpeedsSupplier is None | ||
): | ||
raise RuntimeError( | ||
f"Failed to instantiate MecanumControllerCommand, one of the arguments passed in was None " | ||
) | ||
|
||
self._frontLeftController = frontLeftController | ||
self._rearLeftController = rearLeftController | ||
self._frontRightController = frontRightController | ||
self._rearRightController = rearRightController | ||
|
||
if currentWheelSpeedsSupplier is None: | ||
raise RuntimeError( | ||
f"Failed to instantiate MecanumControllerCommand, no WheelSpeedSupplierProvided." | ||
) | ||
|
||
self._currentWheelSpeeds = currentWheelSpeedsSupplier | ||
|
||
if feedforward is None: | ||
raise RuntimeError( | ||
f"Failed to instantiate MecanumControllerCommand, no SimpleMotorFeedforwardMeters supplied." | ||
) | ||
|
||
self._feedforward = feedforward | ||
|
||
# All the optional requirements verify, set usePid flag to True | ||
self._usePID = True | ||
|
||
# Set the requirements for the command | ||
self.addRequirements(*requirements) | ||
|
||
self._timer = Timer() | ||
|
||
def initialize(self): | ||
initialState = self._trajectory.sample(0) | ||
initialXVelocity = initialState.velocity * initialState.pose.rotation().cos() | ||
initialYVelocity = initialState.velocity * initialState.pose.rotation().sin() | ||
self.m_prevSpeeds = self._kinematics.toWheelSpeeds( | ||
ChassisSpeeds(initialXVelocity, initialYVelocity, 0.0) | ||
) | ||
self._timer.restart() | ||
|
||
def execute(self): | ||
curTime = self._timer.get() | ||
dt = curTime - self._prevTime | ||
desiredState = self._trajectory.sample(curTime) | ||
targetChassisSpeeds = self._controller.calculate( | ||
self._pose(), desiredState, desiredState.pose.rotation() | ||
) | ||
targetWheelSpeeds = self._kinematics.toWheelSpeeds(targetChassisSpeeds) | ||
targetWheelSpeeds.desaturate(self._maxWheelVelocityMetersPerSecond) | ||
frontLeftSpeedSetpoint = targetWheelSpeeds.frontLeft | ||
rearLeftSpeedSetpoint = targetWheelSpeeds.rearLeft | ||
frontRightSpeedSetpoint = targetWheelSpeeds.frontRight | ||
rearRightSpeedSetpoint = targetWheelSpeeds.rearRight | ||
|
||
if not self._usePID: | ||
self._outputConsumer( | ||
MecanumDriveWheelSpeeds( | ||
frontLeftSpeedSetpoint, | ||
frontRightSpeedSetpoint, | ||
rearLeftSpeedSetpoint, | ||
rearRightSpeedSetpoint, | ||
) | ||
) | ||
else: | ||
frontLeftFeedforward = self._feedforward.calculate( | ||
frontLeftSpeedSetpoint, | ||
(frontLeftSpeedSetpoint - self.m_prevSpeeds.frontLeft) / dt, | ||
) | ||
rearLeftFeedforward = self._feedforward.calculate( | ||
rearLeftSpeedSetpoint, | ||
(rearLeftSpeedSetpoint - self.m_prevSpeeds.rearLeft) / dt, | ||
) | ||
frontRightFeedforward = self._feedforward.calculate( | ||
frontRightSpeedSetpoint, | ||
(frontRightSpeedSetpoint - self.m_prevSpeeds.frontRight) / dt, | ||
) | ||
rearRightFeedforward = self._feedforward.calculate( | ||
rearRightSpeedSetpoint, | ||
(rearRightSpeedSetpoint - self.m_prevSpeeds.rearRight) / dt, | ||
) | ||
frontLeftOutput = ( | ||
frontLeftFeedforward | ||
+ self._frontLeftController.calculate( | ||
self._currentWheelSpeeds().frontLeft, | ||
frontLeftSpeedSetpoint, | ||
) | ||
) | ||
rearLeftOutput = rearLeftFeedforward + self._rearLeftController.calculate( | ||
self._currentWheelSpeeds().rearLeft, | ||
rearLeftSpeedSetpoint, | ||
) | ||
frontRightOutput = ( | ||
frontRightFeedforward | ||
+ self._frontRightController.calculate( | ||
self._currentWheelSpeeds().frontRight, | ||
frontRightSpeedSetpoint, | ||
) | ||
) | ||
rearRightOutput = ( | ||
rearRightFeedforward | ||
+ self._rearRightController.calculate( | ||
self._currentWheelSpeeds().rearRight, | ||
rearRightSpeedSetpoint, | ||
) | ||
) | ||
self._outputConsumer( | ||
frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput | ||
) | ||
|
||
# Store current call information for next call | ||
self._prevTime = curTime | ||
self.m_prevSpeeds = targetWheelSpeeds | ||
|
||
def end(self, interrupted): | ||
self._timer.stop() | ||
|
||
def isFinished(self): | ||
return self._timer.hasElapsed(self._trajectory.totalTime()) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,156 @@ | ||
# 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. | ||
|
||
from typing import TYPE_CHECKING, List | ||
import math | ||
|
||
import wpimath.controller as controller | ||
import wpimath.trajectory as trajectory | ||
import wpimath.geometry as geometry | ||
import wpimath.kinematics as kinematics | ||
from wpilib import Timer | ||
|
||
from util import * # type: ignore | ||
|
||
if TYPE_CHECKING: | ||
from .util import * | ||
|
||
import pytest | ||
|
||
import commands2 | ||
|
||
|
||
class MecanumControllerCommandTestDataFixtures: | ||
def __init__(self): | ||
self.timer = Timer() | ||
self.angle: geometry.Rotation2d = geometry.Rotation2d(0) | ||
|
||
# Track speeds and distances | ||
self.frontLeftSpeed = 0 | ||
self.frontLeftDistance = 0 | ||
self.rearLeftSpeed = 0 | ||
self.rearLeftDistance = 0 | ||
self.frontRightSpeed = 0 | ||
self.frontRightDistance = 0 | ||
self.rearRightSpeed = 0 | ||
self.rearRightDistance = 0 | ||
|
||
# Profile Controller and constraints | ||
trapProfileConstraints: trajectory.TrapezoidProfileRadians.Constraints = ( | ||
trajectory.TrapezoidProfileRadians.Constraints(3 * math.pi, math.pi) | ||
) | ||
self.rotationController: controller.ProfiledPIDControllerRadians = ( | ||
controller.ProfiledPIDControllerRadians( | ||
1.0, 0.0, 0.0, trapProfileConstraints | ||
) | ||
) | ||
|
||
# Chassis/Drivetrain constants | ||
self.kxTolerance = 1 / 12.0 | ||
self.kyTolerance = 1 / 12.0 | ||
self.kAngularTolerance = 1 / 12.0 | ||
self.kWheelBase = 0.5 | ||
self.kTrackWidth = 0.5 | ||
|
||
self.command_kinematics: kinematics.MecanumDriveKinematics = ( | ||
kinematics.MecanumDriveKinematics( | ||
geometry.Translation2d(self.kWheelBase / 2, self.kTrackWidth / 2), | ||
geometry.Translation2d(self.kWheelBase / 2, -self.kTrackWidth / 2), | ||
geometry.Translation2d(self.kWheelBase / 2, self.kTrackWidth / 2), | ||
geometry.Translation2d(self.kWheelBase / 2, -self.kTrackWidth / 2), | ||
) | ||
) | ||
|
||
self.command_odometry: kinematics.MecanumDriveOdometry = ( | ||
kinematics.MecanumDriveOdometry( | ||
self.command_kinematics, | ||
geometry.Rotation2d(0), | ||
kinematics.MecanumDriveWheelPositions(), | ||
geometry.Pose2d(0, 0, geometry.Rotation2d(0)), | ||
) | ||
) | ||
|
||
def setWheelSpeeds(self, wheelSpeeds: kinematics.MecanumDriveWheelSpeeds) -> None: | ||
self.frontLeftSpeed = wheelSpeeds.frontLeft | ||
self.rearLeftSpeed = wheelSpeeds.rearLeft | ||
self.frontRightSpeed = wheelSpeeds.frontRight | ||
self.rearRightSpeed = wheelSpeeds.rearRight | ||
|
||
def getCurrentWheelDistances(self) -> kinematics.MecanumDriveWheelPositions: | ||
positions = kinematics.MecanumDriveWheelPositions() | ||
positions.frontLeft = self.frontLeftDistance | ||
positions.frontRight = self.frontRightDistance | ||
positions.rearLeft = self.rearLeftDistance | ||
positions.rearRight = self.rearRightDistance | ||
|
||
return positions | ||
|
||
def getRobotPose(self) -> geometry.Pose2d: | ||
self.command_odometry.update(self.angle, self.getCurrentWheelDistances()) | ||
return self.command_odometry.getPose() | ||
|
||
|
||
@pytest.fixture() | ||
def get_mec_controller_data() -> MecanumControllerCommandTestDataFixtures: | ||
return MecanumControllerCommandTestDataFixtures() | ||
|
||
|
||
def test_mecanumControllerCommand( | ||
scheduler: commands2.CommandScheduler, get_mec_controller_data | ||
): | ||
with ManualSimTime() as sim: | ||
subsystem = commands2.Subsystem() | ||
waypoints: List[geometry.Pose2d] = [] | ||
waypoints.append(geometry.Pose2d(0, 0, geometry.Rotation2d(0))) | ||
waypoints.append(geometry.Pose2d(1, 5, geometry.Rotation2d(3))) | ||
traj_config: trajectory.TrajectoryConfig = trajectory.TrajectoryConfig(8.8, 0.1) | ||
new_trajectory: trajectory.Trajectory = ( | ||
trajectory.TrajectoryGenerator.generateTrajectory(waypoints, traj_config) | ||
) | ||
end_state = new_trajectory.sample(new_trajectory.totalTime()) | ||
|
||
fixture_data = get_mec_controller_data | ||
|
||
mecContCommand = commands2.MecanumControllerCommand( | ||
new_trajectory, | ||
fixture_data.getRobotPose, | ||
fixture_data.command_kinematics, | ||
controller.PIDController(0.6, 0, 0), | ||
controller.PIDController(0.6, 0, 0), | ||
fixture_data.rotationController, | ||
8.8, | ||
fixture_data.setWheelSpeeds, | ||
subsystem, | ||
) | ||
|
||
fixture_data.timer.restart() | ||
|
||
mecContCommand.initialize() | ||
|
||
while not mecContCommand.isFinished(): | ||
mecContCommand.execute() | ||
fixture_data.angle = new_trajectory.sample( | ||
fixture_data.timer.get() | ||
).pose.rotation() | ||
|
||
fixture_data.frontLeftDistance += fixture_data.frontLeftSpeed * 0.005 | ||
fixture_data.rearLeftDistance += fixture_data.rearLeftSpeed * 0.005 | ||
fixture_data.frontRightDistance += fixture_data.frontRightSpeed * 0.005 | ||
fixture_data.rearRightDistance += fixture_data.rearRightSpeed * 0.005 | ||
|
||
sim.step(0.005) | ||
|
||
fixture_data.timer.stop() | ||
mecContCommand.end(True) | ||
|
||
assert end_state.pose.X() == pytest.approx( | ||
fixture_data.getRobotPose().X(), fixture_data.kxTolerance | ||
) | ||
assert end_state.pose.Y() == pytest.approx( | ||
fixture_data.getRobotPose().Y(), fixture_data.kyTolerance | ||
) | ||
assert end_state.pose.rotation().radians() == pytest.approx( | ||
fixture_data.getRobotPose().rotation().radians(), | ||
fixture_data.kAngularTolerance, | ||
) |
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
If any of
are provided (i.e. not
None
), won't we always get here? This doesn't seem right.