[examples] Sync Java and C++ trajectories in sim example (#3081)

This also shifts the trajectory up and to the right so that the robot is
always visible in the Field GUI during traversal. Some drive constants
and trajectory constraints were also synced between the two languages.
This commit is contained in:
Prateek Machiraju
2021-01-11 23:08:22 -05:00
committed by GitHub
parent 64e72f7103
commit 42c3d52863
3 changed files with 11 additions and 10 deletions

View File

@@ -70,7 +70,7 @@ public final class Constants {
public static final double kDriveGearing = 8;
// Example value only - as above, this must be tuned for your drive!
public static final double kPDriveVel = 0.1;
public static final double kPDriveVel = 8.5;
}
public static final class OIConstants {
@@ -79,7 +79,7 @@ public final class Constants {
public static final class AutoConstants {
public static final double kMaxSpeedMetersPerSecond = 3;
public static final double kMaxAccelerationMetersPerSecondSquared = 6;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
// Reasonable baseline values for a RAMSETE follower in units of meters and seconds
public static final double kRamseteB = 2;

View File

@@ -14,6 +14,7 @@ import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.trajectory.Trajectory;
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
@@ -108,12 +109,12 @@ public class RobotContainer {
// An example trajectory to follow. All units in meters.
Trajectory exampleTrajectory =
TrajectoryGenerator.generateTrajectory(
// Start at the origin facing the +X direction
new Pose2d(0, 0, new Rotation2d(0)),
// Start at (1, 2) facing the +X direction
new Pose2d(1, 2, new Rotation2d(0)),
// Pass through these two interior waypoints, making an 's' curve path
List.of(),
List.of(new Translation2d(2, 3), new Translation2d(3, 1)),
// End 3 meters straight ahead of where we started, facing forward
new Pose2d(6, 6, new Rotation2d(0)),
new Pose2d(4, 2, new Rotation2d(0)),
// Pass config
config);