Skip to content

Commit 8f833fc

Browse files
committed
Merge commit 'e7cb6f5dd945198471b24d5c457ef57ec560d313' into upstream
2 parents 350b0e9 + e7cb6f5 commit 8f833fc

15 files changed

+312
-28
lines changed

commands2/src/cpp/frc2/command/button/CommandGenericHID.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,3 +54,17 @@ Trigger CommandGenericHID::POVUpLeft(frc::EventLoop* loop) const {
5454
Trigger CommandGenericHID::POVCenter(frc::EventLoop* loop) const {
5555
return POV(360, loop);
5656
}
57+
58+
Trigger CommandGenericHID::AxisLessThan(int axis, double threshold,
59+
frc::EventLoop* loop) const {
60+
return Trigger(loop, [this, axis, threshold]() {
61+
return this->GetRawAxis(axis) < threshold;
62+
});
63+
}
64+
65+
Trigger CommandGenericHID::AxisGreaterThan(int axis, double threshold,
66+
frc::EventLoop* loop) const {
67+
return Trigger(loop, [this, axis, threshold]() {
68+
return this->GetRawAxis(axis) > threshold;
69+
});
70+
}

commands2/src/cpp/frc2/command/button/CommandXboxController.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,3 +49,13 @@ Trigger CommandXboxController::Back(frc::EventLoop* loop) const {
4949
Trigger CommandXboxController::Start(frc::EventLoop* loop) const {
5050
return XboxController::Start(loop).CastTo<Trigger>();
5151
}
52+
53+
Trigger CommandXboxController::LeftTrigger(double threshold,
54+
frc::EventLoop* loop) const {
55+
return XboxController::LeftTrigger(threshold, loop).CastTo<Trigger>();
56+
}
57+
58+
Trigger CommandXboxController::RightTrigger(double threshold,
59+
frc::EventLoop* loop) const {
60+
return XboxController::RightTrigger(threshold, loop).CastTo<Trigger>();
61+
}

commands2/src/include/frc2/command/Command.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,7 @@ safe) semantics.
238238
* Decorates this command to only run if this condition is not met. If the
239239
* command is already running and the condition changes to true, the command
240240
* will not stop running. The requirements of this command will be kept for
241-
* the new conditonal command.
241+
* the new conditional command.
242242
*
243243
* @param condition the condition that will prevent the command from running
244244
* @return the decorated command

commands2/src/include/frc2/command/CommandPtr.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -163,7 +163,7 @@ class CommandPtr final {
163163
* Decorates this command to only run if this condition is not met. If the
164164
* command is already running and the condition changes to true, the command
165165
* will not stop running. The requirements of this command will be kept for
166-
* the new conditonal command.
166+
* the new conditional command.
167167
*
168168
* @param condition the condition that will prevent the command from running
169169
* @return the decorated command

commands2/src/include/frc2/command/Commands.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ namespace cmd {
131131
[[nodiscard]] CommandPtr Wait(units::second_t duration);
132132

133133
/**
134-
* Constructs a command that does nothing, finishing once a command becomes
134+
* Constructs a command that does nothing, finishing once a condition becomes
135135
* true.
136136
*
137137
* @param condition the condition

commands2/src/include/frc2/command/MecanumControllerCommand.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -268,7 +268,7 @@ class MecanumControllerCommand
268268
*
269269
* <p>Note: The controllers will *not* set the outputVolts to zero upon
270270
* completion of the path - this is left to the user, since it is not
271-
* appropriate for paths with non-stationary end-states.
271+
* appropriate for paths with nonstationary end-states.
272272
*
273273
* @param trajectory The trajectory to follow.
274274
* @param pose A function that supplies the robot pose - use one
@@ -306,7 +306,7 @@ class MecanumControllerCommand
306306
*
307307
* <p>Note: The controllers will *not* set the outputVolts to zero upon
308308
* completion of the path - this is left to the user, since it is not
309-
* appropriate for paths with non-stationary end-states.
309+
* appropriate for paths with nonstationary end-states.
310310
*
311311
* <p>Note 2: The final rotation of the robot will be set to the rotation of
312312
* the final pose in the trajectory. The robot will not follow the rotations
@@ -346,7 +346,7 @@ class MecanumControllerCommand
346346
*
347347
* <p>Note: The controllers will *not* set the outputVolts to zero upon
348348
* completion of the path - this is left to the user, since it is not
349-
* appropriate for paths with non-stationary end-states.
349+
* appropriate for paths with nonstationary end-states.
350350
*
351351
* @param trajectory The trajectory to follow.
352352
* @param pose A function that supplies the robot pose - use one
@@ -384,7 +384,7 @@ class MecanumControllerCommand
384384
*
385385
* <p>Note: The controllers will *not* set the outputVolts to zero upon
386386
* completion of the path - this is left to the user, since it is not
387-
* appropriate for paths with non-stationary end-states.
387+
* appropriate for paths with nonstationary end-states.
388388
*
389389
* <p>Note2: The final rotation of the robot will be set to the rotation of
390390
* the final pose in the trajectory. The robot will not follow the rotations

commands2/src/include/frc2/command/ParallelCommandGroup.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class ParallelCommandGroup
5959

6060
ParallelCommandGroup(ParallelCommandGroup&& other) = default;
6161

62-
// No copy constructors for commandgroups
62+
// No copy constructors for command groups
6363
ParallelCommandGroup(const ParallelCommandGroup&) = delete;
6464

6565
// Prevent template expansion from emulating copy ctor

commands2/src/include/frc2/command/SelectCommand.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ template <typename Key>
3838
class SelectCommand : public CommandHelper<CommandBase, SelectCommand<Key>> {
3939
public:
4040
/**
41-
* Creates a new selectcommand.
41+
* Creates a new SelectCommand.
4242
*
4343
* @param commands the map of commands to choose from
4444
* @param selector the selector to determine which command to run

commands2/src/include/frc2/command/Subsystem.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ class CommandPtr;
3838
*/
3939
class Subsystem {
4040
public:
41-
~Subsystem();
41+
virtual ~Subsystem();
4242
/**
4343
* This method is called periodically by the CommandScheduler. Useful for
4444
* updating subsystem-specific state that you don't want to offload to a

commands2/src/include/frc2/command/SwerveControllerCommand.h

Lines changed: 125 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,131 @@ class SwerveControllerCommand
209209
output,
210210
std::span<Subsystem* const> requirements = {});
211211

212+
/**
213+
* Constructs a new SwerveControllerCommand that when executed will follow the
214+
* provided trajectory. This command will not return output voltages but
215+
* rather raw module states from the position controllers which need to be put
216+
* into a velocity PID.
217+
*
218+
* <p>Note: The controllers will *not* set the outputVolts to zero upon
219+
* completion of the path- this is left to the user, since it is not
220+
* appropriate for paths with nonstationary endstates.
221+
*
222+
* @param trajectory The trajectory to follow.
223+
* @param pose A function that supplies the robot pose,
224+
* provided by the odometry class.
225+
* @param kinematics The kinematics for the robot drivetrain.
226+
* @param controller The HolonomicDriveController for the drivetrain.
227+
* @param desiredRotation The angle that the drivetrain should be
228+
* facing. This is sampled at each time step.
229+
* @param output The raw output module states from the
230+
* position controllers.
231+
* @param requirements The subsystems to require.
232+
*/
233+
SwerveControllerCommand(
234+
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
235+
frc::SwerveDriveKinematics<NumModules> kinematics,
236+
frc::HolonomicDriveController controller,
237+
std::function<frc::Rotation2d()> desiredRotation,
238+
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
239+
output,
240+
std::initializer_list<Subsystem*> requirements);
241+
242+
/**
243+
* Constructs a new SwerveControllerCommand that when executed will follow the
244+
* provided trajectory. This command will not return output voltages but
245+
* rather raw module states from the position controllers which need to be put
246+
* into a velocity PID.
247+
*
248+
* <p>Note: The controllers will *not* set the outputVolts to zero upon
249+
* completion of the path- this is left to the user, since it is not
250+
* appropriate for paths with nonstationary endstates.
251+
*
252+
* <p>Note 2: The final rotation of the robot will be set to the rotation of
253+
* the final pose in the trajectory. The robot will not follow the rotations
254+
* from the poses at each timestep. If alternate rotation behavior is desired,
255+
* the other constructor with a supplier for rotation should be used.
256+
*
257+
* @param trajectory The trajectory to follow.
258+
* @param pose A function that supplies the robot pose,
259+
* provided by the odometry class.
260+
* @param kinematics The kinematics for the robot drivetrain.
261+
* @param controller The HolonomicDriveController for the drivetrain.
262+
* @param output The raw output module states from the
263+
* position controllers.
264+
* @param requirements The subsystems to require.
265+
*/
266+
SwerveControllerCommand(
267+
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
268+
frc::SwerveDriveKinematics<NumModules> kinematics,
269+
frc::HolonomicDriveController controller,
270+
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
271+
output,
272+
std::initializer_list<Subsystem*> requirements);
273+
274+
/**
275+
* Constructs a new SwerveControllerCommand that when executed will follow the
276+
* provided trajectory. This command will not return output voltages but
277+
* rather raw module states from the position controllers which need to be put
278+
* into a velocity PID.
279+
*
280+
* <p>Note: The controllers will *not* set the outputVolts to zero upon
281+
* completion of the path- this is left to the user, since it is not
282+
* appropriate for paths with nonstationary endstates.
283+
*
284+
*
285+
* @param trajectory The trajectory to follow.
286+
* @param pose A function that supplies the robot pose,
287+
* provided by the odometry class.
288+
* @param kinematics The kinematics for the robot drivetrain.
289+
* @param controller The HolonomicDriveController for the robot.
290+
* @param desiredRotation The angle that the drivetrain should be
291+
* facing. This is sampled at each time step.
292+
* @param output The raw output module states from the
293+
* position controllers.
294+
* @param requirements The subsystems to require.
295+
*/
296+
SwerveControllerCommand(
297+
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
298+
frc::SwerveDriveKinematics<NumModules> kinematics,
299+
frc::HolonomicDriveController controller,
300+
std::function<frc::Rotation2d()> desiredRotation,
301+
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
302+
output,
303+
std::span<Subsystem* const> requirements = {});
304+
305+
/**
306+
* Constructs a new SwerveControllerCommand that when executed will follow the
307+
* provided trajectory. This command will not return output voltages but
308+
* rather raw module states from the position controllers which need to be put
309+
* into a velocity PID.
310+
*
311+
* <p>Note: The controllers will *not* set the outputVolts to zero upon
312+
* completion of the path- this is left to the user, since it is not
313+
* appropriate for paths with nonstationary endstates.
314+
*
315+
* <p>Note 2: The final rotation of the robot will be set to the rotation of
316+
* the final pose in the trajectory. The robot will not follow the rotations
317+
* from the poses at each timestep. If alternate rotation behavior is desired,
318+
* the other constructor with a supplier for rotation should be used.
319+
*
320+
* @param trajectory The trajectory to follow.
321+
* @param pose A function that supplies the robot pose,
322+
* provided by the odometry class.
323+
* @param kinematics The kinematics for the robot drivetrain.
324+
* @param controller The HolonomicDriveController for the drivetrain.
325+
* @param output The raw output module states from the
326+
* position controllers.
327+
* @param requirements The subsystems to require.
328+
*/
329+
SwerveControllerCommand(
330+
frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
331+
frc::SwerveDriveKinematics<NumModules> kinematics,
332+
frc::HolonomicDriveController controller,
333+
std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
334+
output,
335+
std::span<Subsystem* const> requirements = {});
336+
212337
void Initialize() override;
213338

214339
void Execute() override;

0 commit comments

Comments
 (0)