Skip to content
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

Dev splines test 2022 #279

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 23 additions & 12 deletions commands/chassis/SimpleSplines.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,21 +23,32 @@

public class SimpleSplines extends SequentialCommandGroup {
public SimpleSplines(SplinesDrive robotDrive, Pose2d init_pos, List<Translation2d> inter_points, Pose2d final_pos, double maxVoltage, Command nextCommand){
super(new RamseteCommand(
TrajectoryGenerator.generateTrajectory(init_pos, inter_points, final_pos, new TrajectoryConfig(robotDrive.getAutoConstants().kMaxSpeedMetersPerSecond,
robotDrive.getAutoConstants().kMaxAccelerationMetersPerSecondSquared)
.setKinematics(robotDrive.getDriveConstants().kDriveKinematics)
.addConstraint(new DifferentialDriveVoltageConstraint(
new SimpleMotorFeedforward(robotDrive.getDriveConstants().ksVolts,
robotDrive.getDriveConstants().kvVoltSecondsPerMeter,
robotDrive.getDriveConstants().kaVoltSecondsSquaredPerMeter),
super(
new RamseteCommand(
TrajectoryGenerator.generateTrajectory(init_pos, inter_points, final_pos,
new TrajectoryConfig(
robotDrive.getAutoConstants().kMaxSpeedMetersPerSecond,
robotDrive.getAutoConstants().kMaxAccelerationMetersPerSecondSquared
).setKinematics(robotDrive.getDriveConstants().kDriveKinematics
).addConstraint(
new DifferentialDriveVoltageConstraint(
new SimpleMotorFeedforward(
robotDrive.getDriveConstants().ksVolts,
robotDrive.getDriveConstants().kvVoltSecondsPerMeter,
robotDrive.getDriveConstants().kaVoltSecondsSquaredPerMeter
),
robotDrive.getDriveConstants().kDriveKinematics,
maxVoltage))),
maxVoltage
)
)
),
robotDrive::getPose,
new RamseteController(robotDrive.getAutoConstants().kRamseteB, robotDrive.getAutoConstants().kRamseteZeta),
new SimpleMotorFeedforward(robotDrive.getDriveConstants().ksVolts,
robotDrive.getDriveConstants().kvVoltSecondsPerMeter,
robotDrive.getDriveConstants().kaVoltSecondsSquaredPerMeter),
new SimpleMotorFeedforward(
robotDrive.getDriveConstants().ksVolts,
robotDrive.getDriveConstants().kvVoltSecondsPerMeter,
robotDrive.getDriveConstants().kaVoltSecondsSquaredPerMeter
),
robotDrive.getDriveConstants().kDriveKinematics,
robotDrive::getWheelSpeeds,
new PIDController(robotDrive.getDriveConstants().kPDriveVel, 0, 0),
Expand Down
4 changes: 1 addition & 3 deletions subsystems/chassis/SplinesDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,10 @@

package org.usfirst.frc4904.standard.subsystems.chassis;

import javax.naming.InitialContext;

import com.ctre.phoenix.sensors.CANCoder;
import org.usfirst.frc4904.standard.custom.sensors.CANTalonEncoder;

import org.usfirst.frc4904.standard.commands.chassis.SimpleSplines;
import org.usfirst.frc4904.standard.custom.sensors.CANTalonEncoder;
import org.usfirst.frc4904.standard.custom.sensors.IMU;
import org.usfirst.frc4904.standard.subsystems.chassis.TankDrive;
import org.usfirst.frc4904.standard.subsystems.motor.Motor;
Expand Down