@@ -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