diff --git a/pathplannerlib/src/main/java/com/pathplanner/lib/auto/AutoBuilder.java b/pathplannerlib/src/main/java/com/pathplanner/lib/auto/AutoBuilder.java index ea3ac839..b149a450 100644 --- a/pathplannerlib/src/main/java/com/pathplanner/lib/auto/AutoBuilder.java +++ b/pathplannerlib/src/main/java/com/pathplanner/lib/auto/AutoBuilder.java @@ -1,9 +1,7 @@ package com.pathplanner.lib.auto; -import com.pathplanner.lib.commands.FollowPathHolonomic; -import com.pathplanner.lib.commands.FollowPathLTV; -import com.pathplanner.lib.commands.FollowPathRamsete; -import com.pathplanner.lib.commands.FollowPathWithEvents; +import com.pathplanner.lib.commands.*; +import com.pathplanner.lib.path.PathConstraints; import com.pathplanner.lib.path.PathPlannerPath; import com.pathplanner.lib.util.HolonomicPathFollowerConfig; import com.pathplanner.lib.util.ReplanningConfig; @@ -34,6 +32,13 @@ public class AutoBuilder { private static Supplier getPose; private static Consumer resetPose; + // Pathfinding builders + private static boolean pathfindingConfigured = false; + private static QuadFunction + pathfindToPoseCommandBuilder; + private static TriFunction + pathfindThenFollowPathCommandBuilder; + /** * Configures the AutoBuilder for a holonomic drivetrain. * @@ -71,6 +76,31 @@ public static void configureHolonomic( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindToPoseCommandBuilder = + (pose, constraints, goalEndVel, rotationDelayDistance) -> + new PathfindHolonomic( + pose, + constraints, + goalEndVel, + poseSupplier, + robotRelativeSpeedsSupplier, + robotRelativeOutput, + config, + rotationDelayDistance, + driveSubsystem); + AutoBuilder.pathfindThenFollowPathCommandBuilder = + (path, constraints, rotationDelayDistance) -> + new PathfindThenFollowPathHolonomic( + path, + constraints, + poseSupplier, + robotRelativeSpeedsSupplier, + robotRelativeOutput, + config, + rotationDelayDistance, + driveSubsystem); + AutoBuilder.pathfindingConfigured = true; } /** @@ -103,6 +133,28 @@ public static void configureRamsete( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindToPoseCommandBuilder = + (pose, constraints, goalEndVel, rotationDelayDistance) -> + new PathfindRamsete( + pose.getTranslation(), + constraints, + goalEndVel, + poseSupplier, + speedsSupplier, + output, + driveSubsystem); + AutoBuilder.pathfindThenFollowPathCommandBuilder = + (path, constraints, rotationDelayDistance) -> + new PathfindThenFollowPathRamsete( + path, + constraints, + poseSupplier, + speedsSupplier, + output, + replanningConfig, + driveSubsystem); + AutoBuilder.pathfindingConfigured = true; } /** @@ -148,6 +200,32 @@ public static void configureRamsete( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindToPoseCommandBuilder = + (pose, constraints, goalEndVel, rotationDelayDistance) -> + new PathfindRamsete( + pose.getTranslation(), + constraints, + goalEndVel, + poseSupplier, + speedsSupplier, + output, + b, + zeta, + driveSubsystem); + AutoBuilder.pathfindThenFollowPathCommandBuilder = + (path, constraints, rotationDelayDistance) -> + new PathfindThenFollowPathRamsete( + path, + constraints, + poseSupplier, + speedsSupplier, + output, + b, + zeta, + replanningConfig, + driveSubsystem); + AutoBuilder.pathfindingConfigured = true; } /** @@ -183,6 +261,30 @@ public static void configureLTV( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindToPoseCommandBuilder = + (pose, constraints, goalEndVel, rotationDelayDistance) -> + new PathfindLTV( + pose.getTranslation(), + constraints, + goalEndVel, + poseSupplier, + speedsSupplier, + output, + dt, + driveSubsystem); + AutoBuilder.pathfindThenFollowPathCommandBuilder = + (path, constraints, rotationDelayDistance) -> + new PathfindThenFollowPathLTV( + path, + constraints, + poseSupplier, + speedsSupplier, + output, + dt, + replanningConfig, + driveSubsystem); + AutoBuilder.pathfindingConfigured = true; } /** @@ -230,10 +332,39 @@ public static void configureLTV( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindToPoseCommandBuilder = + (pose, constraints, goalEndVel, rotationDelayDistance) -> + new PathfindLTV( + pose.getTranslation(), + constraints, + goalEndVel, + poseSupplier, + speedsSupplier, + output, + qelems, + relems, + dt, + driveSubsystem); + AutoBuilder.pathfindThenFollowPathCommandBuilder = + (path, constraints, rotationDelayDistance) -> + new PathfindThenFollowPathLTV( + path, + constraints, + poseSupplier, + speedsSupplier, + output, + qelems, + relems, + dt, + replanningConfig, + driveSubsystem); + AutoBuilder.pathfindingConfigured = true; } /** - * Configures the AutoBuilder with custom path following command builder. + * Configures the AutoBuilder with custom path following command builder. Building pathfinding + * commands is not supported if using a custom command builder. * * @param pathFollowingCommandBuilder a function that builds a command to follow a given path * @param poseSupplier a supplier for the robot's current pose @@ -253,6 +384,8 @@ public static void configureCustom( AutoBuilder.getPose = poseSupplier; AutoBuilder.resetPose = resetPose; AutoBuilder.configured = true; + + AutoBuilder.pathfindingConfigured = false; } /** @@ -264,6 +397,15 @@ public static boolean isConfigured() { return configured; } + /** + * Returns whether the AutoBuilder has been configured for pathfinding. + * + * @return true if the AutoBuilder has been configured for pathfinding, false otherwise + */ + public static boolean isPathfindingConfigured() { + return pathfindingConfigured; + } + /** * Builds a command to follow a path with event markers. * @@ -280,6 +422,92 @@ public static Command followPathWithEvents(PathPlannerPath path) { return new FollowPathWithEvents(pathFollowingCommandBuilder.apply(path), path, getPose); } + /** + * Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose + * rotation and rotation delay distance will have no effect. + * + * @param pose The pose to pathfind to + * @param constraints The constraints to use while pathfinding + * @param goalEndVelocity The goal end velocity of the robot when reaching the target pose + * @param rotationDelayDistance The distance the robot should move from the start position before + * attempting to rotate to the final rotation + * @return A command to pathfind to a given pose + */ + public static Command pathfindToPose( + Pose2d pose, + PathConstraints constraints, + double goalEndVelocity, + double rotationDelayDistance) { + if (!isPathfindingConfigured()) { + throw new AutoBuilderException( + "Auto builder was used to build a pathfinding command before being configured"); + } + + return pathfindToPoseCommandBuilder.apply( + pose, constraints, goalEndVelocity, rotationDelayDistance); + } + + /** + * Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose + * rotation will have no effect. + * + * @param pose The pose to pathfind to + * @param constraints The constraints to use while pathfinding + * @param goalEndVelocity The goal end velocity of the robot when reaching the target pose + * @return A command to pathfind to a given pose + */ + public static Command pathfindToPose( + Pose2d pose, PathConstraints constraints, double goalEndVelocity) { + return pathfindToPose(pose, constraints, goalEndVelocity, 0); + } + + /** + * Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose + * rotation will have no effect. + * + * @param pose The pose to pathfind to + * @param constraints The constraints to use while pathfinding + * @return A command to pathfind to a given pose + */ + public static Command pathfindToPose(Pose2d pose, PathConstraints constraints) { + return pathfindToPose(pose, constraints, 0); + } + + /** + * Build a command to pathfind to a given path, then follow that path. If not using a holonomic + * drivetrain, the pose rotation delay distance will have no effect. + * + * @param goalPath The path to pathfind to, then follow + * @param pathfindingConstraints The constraints to use while pathfinding + * @param rotationDelayDistance The distance the robot should move from the start position before + * attempting to rotate to the final rotation + * @return A command to pathfind to a given path, then follow the path + */ + public static Command pathfindThenFollowPath( + PathPlannerPath goalPath, + PathConstraints pathfindingConstraints, + double rotationDelayDistance) { + if (!isPathfindingConfigured()) { + throw new AutoBuilderException( + "Auto builder was used to build a pathfinding command before being configured"); + } + + return pathfindThenFollowPathCommandBuilder.apply( + goalPath, pathfindingConstraints, rotationDelayDistance); + } + + /** + * Build a command to pathfind to a given path, then follow that path. + * + * @param goalPath The path to pathfind to, then follow + * @param pathfindingConstraints The constraints to use while pathfinding + * @return A command to pathfind to a given path, then follow the path + */ + public static Command pathfindThenFollowPath( + PathPlannerPath goalPath, PathConstraints pathfindingConstraints) { + return pathfindThenFollowPath(goalPath, pathfindingConstraints, 0); + } + /** * Get the starting pose from its JSON representation. This is only used internally. * @@ -340,4 +568,33 @@ public static Command getAutoCommandFromJson(JSONObject autoJson) { return autoCommand; } } + + /** Functional interface for a function that takes 3 inputs */ + @FunctionalInterface + public interface TriFunction { + /** + * Apply the inputs to this function + * + * @param in1 Input 1 + * @param in2 Input 2 + * @param in3 Input 3 + * @return Output + */ + Out apply(In1 in1, In2 in2, In3 in3); + } + + /** Functional interface for a function that takes 4 inputs */ + @FunctionalInterface + public interface QuadFunction { + /** + * Apply the inputs to this function + * + * @param in1 Input 1 + * @param in2 Input 2 + * @param in3 Input 3 + * @param in4 Input 4 + * @return Output + */ + Out apply(In1 in1, In2 in2, In3 in3, In4 in4); + } } diff --git a/pathplannerlib/src/main/java/org/json/simple/parser/Yylex.java b/pathplannerlib/src/main/java/org/json/simple/parser/Yylex.java index 3a88f399..6e761af6 100755 --- a/pathplannerlib/src/main/java/org/json/simple/parser/Yylex.java +++ b/pathplannerlib/src/main/java/org/json/simple/parser/Yylex.java @@ -467,8 +467,7 @@ else if (zzAtEOF) { break; case 1: { - throw new ParseException( - yychar, ParseException.ERROR_UNEXPECTED_CHAR, new Character(yycharat(0))); + throw new ParseException(yychar, ParseException.ERROR_UNEXPECTED_CHAR, yycharat(0)); } case 34: break; diff --git a/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp b/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp index 389f03e3..56a7ecf4 100644 --- a/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp +++ b/pathplannerlib/src/main/native/cpp/pathplanner/lib/auto/AutoBuilder.cpp @@ -3,6 +3,12 @@ #include "pathplanner/lib/commands/FollowPathRamsete.h" #include "pathplanner/lib/commands/FollowPathLTV.h" #include "pathplanner/lib/commands/FollowPathWithEvents.h" +#include "pathplanner/lib/commands/PathfindHolonomic.h" +#include "pathplanner/lib/commands/PathfindThenFollowPathHolonomic.h" +#include "pathplanner/lib/commands/PathfindRamsete.h" +#include "pathplanner/lib/commands/PathfindThenFollowPathRamsete.h" +#include "pathplanner/lib/commands/PathfindLTV.h" +#include "pathplanner/lib/commands/PathfindThenFollowPathLTV.h" #include "pathplanner/lib/auto/CommandUtil.h" #include #include @@ -16,6 +22,14 @@ std::function)> AutoBuilder::m std::function AutoBuilder::m_getPose; std::function AutoBuilder::m_resetPose; +bool AutoBuilder::m_pathfindingConfigured = false; +std::function< + frc2::CommandPtr(frc::Pose2d, PathConstraints, + units::meters_per_second_t, units::meter_t)> AutoBuilder::m_pathfindToPoseCommandBuilder; +std::function< + frc2::CommandPtr(std::shared_ptr, PathConstraints, + units::meter_t)> AutoBuilder::m_pathfindThenFollowPathCommandBuilder; + void AutoBuilder::configureHolonomic(std::function poseSupplier, std::function resetPose, std::function robotRelativeSpeedsSupplier, @@ -36,6 +50,25 @@ void AutoBuilder::configureHolonomic(std::function poseSupplier, AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindToPoseCommandBuilder = [poseSupplier, + robotRelativeSpeedsSupplier, robotRelativeOutput, config, + driveSubsystem](frc::Pose2d pose, PathConstraints constraints, + units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + return PathfindHolonomic(pose, constraints, goalEndVel, poseSupplier, + robotRelativeSpeedsSupplier, robotRelativeOutput, config, { + driveSubsystem }, rotationDelayDistance).ToPtr(); + }; + AutoBuilder::m_pathfindThenFollowPathCommandBuilder = [poseSupplier, + robotRelativeSpeedsSupplier, robotRelativeOutput, config, + driveSubsystem](std::shared_ptr path, + PathConstraints constraints, units::meter_t rotationDelayDistance) { + return PathfindThenFollowPathHolonomic(path, constraints, poseSupplier, + robotRelativeSpeedsSupplier, robotRelativeOutput, config, { + driveSubsystem }, rotationDelayDistance).ToPtr(); + }; + AutoBuilder::m_pathfindingConfigured = true; } void AutoBuilder::configureRamsete(std::function poseSupplier, @@ -57,6 +90,26 @@ void AutoBuilder::configureRamsete(std::function poseSupplier, AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindToPoseCommandBuilder = + [poseSupplier, speedsSupplier, output, driveSubsystem]( + frc::Pose2d pose, PathConstraints constraints, + units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + return PathfindRamsete(pose.Translation(), constraints, + goalEndVel, poseSupplier, speedsSupplier, output, { + driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindThenFollowPathCommandBuilder = + [poseSupplier, speedsSupplier, output, replanningConfig, + driveSubsystem](std::shared_ptr path, + PathConstraints constraints, + units::meter_t rotationDelayDistance) { + return PathfindThenFollowPathRamsete(path, constraints, + poseSupplier, speedsSupplier, output, replanningConfig, + { driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindingConfigured = true; } void AutoBuilder::configureRamsete(std::function poseSupplier, @@ -80,6 +133,24 @@ void AutoBuilder::configureRamsete(std::function poseSupplier, AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindToPoseCommandBuilder = [poseSupplier, speedsSupplier, + output, b, zeta, driveSubsystem](frc::Pose2d pose, + PathConstraints constraints, units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + return PathfindRamsete(pose.Translation(), constraints, goalEndVel, + poseSupplier, speedsSupplier, output, b, zeta, + { driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindThenFollowPathCommandBuilder = [poseSupplier, + speedsSupplier, output, b, zeta, replanningConfig, driveSubsystem]( + std::shared_ptr path, PathConstraints constraints, + units::meter_t rotationDelayDistance) { + return PathfindThenFollowPathRamsete(path, constraints, poseSupplier, + speedsSupplier, output, b, zeta, replanningConfig, { + driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindingConfigured = true; } void AutoBuilder::configureLTV(std::function poseSupplier, @@ -103,6 +174,24 @@ void AutoBuilder::configureLTV(std::function poseSupplier, AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindToPoseCommandBuilder = [poseSupplier, speedsSupplier, + output, Qelms, Relms, dt, driveSubsystem](frc::Pose2d pose, + PathConstraints constraints, units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + return PathfindLTV(pose.Translation(), constraints, goalEndVel, + poseSupplier, speedsSupplier, output, Qelms, Relms, dt, { + driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindThenFollowPathCommandBuilder = [poseSupplier, + speedsSupplier, output, Qelms, Relms, dt, replanningConfig, + driveSubsystem](std::shared_ptr path, + PathConstraints constraints, units::meter_t rotationDelayDistance) { + return PathfindThenFollowPathLTV(path, constraints, poseSupplier, + speedsSupplier, output, Qelms, Relms, dt, replanningConfig, { + driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindingConfigured = true; } void AutoBuilder::configureLTV(std::function poseSupplier, @@ -124,6 +213,25 @@ void AutoBuilder::configureLTV(std::function poseSupplier, AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindToPoseCommandBuilder = + [poseSupplier, speedsSupplier, output, dt, driveSubsystem]( + frc::Pose2d pose, PathConstraints constraints, + units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + return PathfindLTV(pose.Translation(), constraints, goalEndVel, + poseSupplier, speedsSupplier, output, dt, { + driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindThenFollowPathCommandBuilder = [poseSupplier, + speedsSupplier, output, dt, replanningConfig, driveSubsystem]( + std::shared_ptr path, PathConstraints constraints, + units::meter_t rotationDelayDistance) { + return PathfindThenFollowPathLTV(path, constraints, poseSupplier, + speedsSupplier, output, dt, replanningConfig, + { driveSubsystem }).ToPtr(); + }; + AutoBuilder::m_pathfindingConfigured = true; } void AutoBuilder::configureCustom( @@ -139,6 +247,8 @@ void AutoBuilder::configureCustom( AutoBuilder::m_getPose = poseSupplier; AutoBuilder::m_resetPose = resetPose; AutoBuilder::m_configured = true; + + AutoBuilder::m_pathfindingConfigured = false; } frc2::CommandPtr AutoBuilder::followPathWithEvents( @@ -192,3 +302,28 @@ frc::Pose2d AutoBuilder::getStartingPoseFromJson(const wpi::json &json) { return frc::Pose2d(x, y, frc::Rotation2d(deg)); } + +frc2::CommandPtr AutoBuilder::pathfindToPose(frc::Pose2d pose, + PathConstraints constraints, units::meters_per_second_t goalEndVel, + units::meter_t rotationDelayDistance) { + if (!m_pathfindingConfigured) { + throw std::runtime_error( + "Auto builder was used to build a pathfinding command before being configured"); + } + + return m_pathfindToPoseCommandBuilder(pose, constraints, goalEndVel, + rotationDelayDistance); +} + +frc2::CommandPtr AutoBuilder::pathfindThenFollowPath( + std::shared_ptr goalPath, + PathConstraints pathfindingConstraints, + units::meter_t rotationDelayDistance) { + if (!m_pathfindingConfigured) { + throw std::runtime_error( + "Auto builder was used to build a pathfinding command before being configured"); + } + + return m_pathfindThenFollowPathCommandBuilder(goalPath, + pathfindingConstraints, rotationDelayDistance); +} diff --git a/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h b/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h index 963ec900..1d6d897c 100644 --- a/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h +++ b/pathplannerlib/src/main/native/include/pathplanner/lib/auto/AutoBuilder.h @@ -113,7 +113,7 @@ class AutoBuilder { ReplanningConfig replanningConfig, frc2::Subsystem *driveSubsystem); /** - * Configures the AutoBuilder with custom path following command builder. + * Configures the AutoBuilder with custom path following command builder. Building pathfinding commands is not supported when using a custom path following command builder. * * @param pathFollowingCommandBuilder a function that builds a command to follow a given path * @param poseSupplier a function that returns the robot's current pose @@ -160,10 +160,48 @@ class AutoBuilder { static frc::Pose2d getStartingPoseFromJson(const wpi::json &json); + /** + * Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose + * rotation and rotation delay distance will have no effect. + * + * @param pose The pose to pathfind to + * @param constraints The constraints to use while pathfinding + * @param goalEndVelocity The goal end velocity of the robot when reaching the target pose + * @param rotationDelayDistance The distance the robot should move from the start position before + * attempting to rotate to the final rotation + * @return A command to pathfind to a given pose + */ + static frc2::CommandPtr pathfindToPose(frc::Pose2d pose, + PathConstraints constraints, units::meters_per_second_t goalEndVel = + 0_mps, units::meter_t rotationDelayDistance = 0_m); + + /** + * Build a command to pathfind to a given path, then follow that path. If not using a holonomic + * drivetrain, the pose rotation delay distance will have no effect. + * + * @param goalPath The path to pathfind to, then follow + * @param pathfindingConstraints The constraints to use while pathfinding + * @param rotationDelayDistance The distance the robot should move from the start position before + * attempting to rotate to the final rotation + * @return A command to pathfind to a given path, then follow the path + */ + static frc2::CommandPtr pathfindThenFollowPath( + std::shared_ptr goalPath, + PathConstraints pathfindingConstraints, + units::meter_t rotationDelayDistance = 0_m); + private: static bool m_configured; static std::function)> m_pathFollowingCommandBuilder; static std::function m_getPose; static std::function m_resetPose; + + static bool m_pathfindingConfigured; + static std::function< + frc2::CommandPtr(frc::Pose2d, PathConstraints, + units::meters_per_second_t, units::meter_t)> m_pathfindToPoseCommandBuilder; + static std::function< + frc2::CommandPtr(std::shared_ptr, PathConstraints, + units::meter_t)> m_pathfindThenFollowPathCommandBuilder; }; } diff --git a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindLTV.h b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindLTV.h index 0209c8be..7d895402 100644 --- a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindLTV.h +++ b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindLTV.h @@ -103,51 +103,5 @@ class PathfindLTV: public PathfindingCommand { goalEndVel, poseSupplier, currentRobotRelativeSpeeds, output, std::make_unique < PPLTVController > (dt), 0_m, requirements) { } - - /** - * Constructs a new PathfindLTV command that will generate a path towards the given position. - * - * @param targetPosition the position to pathfind to - * @param constraints the path constraints to use while pathfinding - * @param poseSupplier a supplier for the robot's current pose - * @param currentRobotRelativeSpeeds a supplier for the robot's current robot relative speeds - * @param output a consumer for the output speeds (robot relative) - * @param Qelems The maximum desired error tolerance for each state. - * @param Relems The maximum desired control effort for each input. - * @param dt Period of the robot control loop in seconds (default 0.02) - * @param requirements the subsystems required by this command - */ - PathfindLTV(frc::Translation2d targetPosition, PathConstraints constraints, - units::meters_per_second_t goalEndVel, - std::function poseSupplier, - std::function currentRobotRelativeSpeeds, - std::function output, - const wpi::array &Qelems, - const wpi::array &Relems, units::second_t dt, - frc2::Requirements requirements) : PathfindLTV(targetPosition, - constraints, 0_mps, poseSupplier, currentRobotRelativeSpeeds, - output, Qelems, Relems, dt, requirements) { - } - - /** - * Constructs a new PathfindLTV command that will generate a path towards the given position. - * - * @param targetPosition the position to pathfind to - * @param constraints the path constraints to use while pathfinding - * @param poseSupplier a supplier for the robot's current pose - * @param currentRobotRelativeSpeeds a supplier for the robot's current robot relative speeds - * @param output a consumer for the output speeds (robot relative) - * @param dt Period of the robot control loop in seconds (default 0.02) - * @param requirements the subsystems required by this command - */ - PathfindLTV(frc::Translation2d targetPosition, PathConstraints constraints, - units::meters_per_second_t goalEndVel, - std::function poseSupplier, - std::function currentRobotRelativeSpeeds, - std::function output, units::second_t dt, - frc2::Requirements requirements) : PathfindLTV(targetPosition, - constraints, 0_mps, poseSupplier, currentRobotRelativeSpeeds, - output, dt, requirements) { - } }; } diff --git a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindRamsete.h b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindRamsete.h index 255f3514..4c36febc 100644 --- a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindRamsete.h +++ b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindRamsete.h @@ -103,51 +103,5 @@ class PathfindRamsete: public PathfindingCommand { goalEndVel, poseSupplier, currentRobotRelativeSpeeds, output, std::make_unique(), 0_m, requirements) { } - - /** - * Constructs a new PathfindRamsete command that will generate a path towards the given position. - * - * @param targetPosition the position to pathfind to - * @param constraints the path constraints to use while pathfinding - * @param poseSupplier a supplier for the robot's current pose - * @param currentRobotRelativeSpeeds a supplier for the robot's current robot relative speeds - * @param output a consumer for the output speeds (robot relative) - * @param b Tuning parameter (b > 0 rad^2/m^2) for which larger values make convergence more - * aggressive like a proportional term. - * @param zeta Tuning parameter (0 rad^-1 < zeta < 1 rad^-1) for which larger values provide - * more damping in response. - * @param requirements the subsystems required by this command - */ - PathfindRamsete(frc::Translation2d targetPosition, - PathConstraints constraints, units::meters_per_second_t goalEndVel, - std::function poseSupplier, - std::function currentRobotRelativeSpeeds, - std::function output, - units::unit_t b, - units::unit_t zeta, - frc2::Requirements requirements) : PathfindRamsete(targetPosition, - constraints, 0_mps, poseSupplier, currentRobotRelativeSpeeds, - output, b, zeta, requirements) { - } - - /** - * Constructs a new PathfindRamsete command that will generate a path towards the given position. - * - * @param targetPosition the position to pathfind to - * @param constraints the path constraints to use while pathfinding - * @param poseSupplier a supplier for the robot's current pose - * @param currentRobotRelativeSpeeds a supplier for the robot's current robot relative speeds - * @param output a consumer for the output speeds (robot relative) - * @param requirements the subsystems required by this command - */ - PathfindRamsete(frc::Translation2d targetPosition, - PathConstraints constraints, units::meters_per_second_t goalEndVel, - std::function poseSupplier, - std::function currentRobotRelativeSpeeds, - std::function output, - frc2::Requirements requirements) : PathfindRamsete(targetPosition, - constraints, 0_mps, poseSupplier, currentRobotRelativeSpeeds, - output, requirements) { - } }; } diff --git a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindThenFollowPathRamsete.h b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindThenFollowPathRamsete.h index 1fe8f633..057d2471 100644 --- a/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindThenFollowPathRamsete.h +++ b/pathplannerlib/src/main/native/include/pathplanner/lib/commands/PathfindThenFollowPathRamsete.h @@ -59,7 +59,7 @@ class PathfindThenFollowPathRamsete: public frc2::SequentialCommandGroup { std::function poseSupplier, std::function currentRobotRelativeSpeeds, std::function robotRelativeOutput, - units::second_t dt, ReplanningConfig replanningConfig, + ReplanningConfig replanningConfig, frc2::Requirements requirements) { AddCommands( PathfindRamsete(goalPath, pathfindingConstraints, poseSupplier,