Skip to content
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
3 changes: 2 additions & 1 deletion src/org/montclairrobotics/sprocket/SprocketRobot.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
package org.montclairrobotics.sprocket;

import edu.wpi.first.wpilibj.IterativeRobot;
import org.montclairrobotics.sprocket.loop.Updater;

import edu.wpi.first.wpilibj.IterativeRobot;

public class SprocketRobot extends IterativeRobot {

@Override
Expand Down
61 changes: 36 additions & 25 deletions src/org/montclairrobotics/sprocket/control/ArcadeDriveInput.java
Original file line number Diff line number Diff line change
@@ -1,53 +1,64 @@
package org.montclairrobotics.sprocket.control;

import edu.wpi.first.wpilibj.Joystick;
import org.montclairrobotics.sprocket.drive.DriveTrainTarget;
import org.montclairrobotics.sprocket.drive.MotorInputType;
import org.montclairrobotics.sprocket.drive.DriveTrainInput;
import org.montclairrobotics.sprocket.geometry.Degrees;
import org.montclairrobotics.sprocket.geometry.Inch;
import org.montclairrobotics.sprocket.geometry.Polar;
import org.montclairrobotics.sprocket.geometry.Angle;
import org.montclairrobotics.sprocket.geometry.Distance;
import org.montclairrobotics.sprocket.geometry.IN;
import org.montclairrobotics.sprocket.geometry.Vector;
import org.montclairrobotics.sprocket.geometry.XY;
import org.montclairrobotics.sprocket.loop.Priority;
import org.montclairrobotics.sprocket.loop.Updatable;
import org.montclairrobotics.sprocket.loop.Updater;
import org.montclairrobotics.sprocket.utils.Input;

import edu.wpi.first.wpilibj.Joystick;

public class ArcadeDriveInput extends DriveTrainInput {
public class ArcadeDriveInput implements Input<DriveTrainTarget>,Updatable {

private Joystick stick;
private boolean speedControl;
private double maxSpeed;
MotorInputType inputType;

//private boolean speedControl;
private Distance maxSpeed;
private Angle maxTurn;

private Vector dir;
private double turn;
private Angle turn;

public ArcadeDriveInput(Joystick stick) {
super(MotorInputType.PERCENT);
speedControl = false;
inputType=MotorInputType.PERCENT;
this.stick = stick;
this.maxSpeed=new IN(1);
this.maxTurn=Angle.QUARTER;
Updater.add(this, Priority.INPUT);
}

public ArcadeDriveInput(Joystick stick, Inch maxSpeed) {
super(MotorInputType.SPEED);
speedControl = true;
public ArcadeDriveInput(Joystick stick, Distance maxSpeed, Angle maxTurn) {
inputType=MotorInputType.SPEED;
this.stick = stick;
this.maxSpeed = maxSpeed.get();
this.maxSpeed = maxSpeed;
this.maxTurn=maxTurn;
Updater.add(this, Priority.INPUT);
}


@Override
public void update() {
turn = stick.getX();
dir = new Polar(stick.getMagnitude(), new Degrees(stick.getDirectionDegrees()));

if(speedControl) {
dir.scale(maxSpeed,false);
}
maxTurn = maxTurn.times(stick.getX());
dir = new XY(0,stick.getY()*maxSpeed.get());
}

@Override
public Vector getDirection() {
return dir;
}

@Override
public double getTurn() {
public Angle getTurn() {
return turn;
}

@Override
public DriveTrainTarget get() {
// TODO Auto-generated method stub
return new DriveTrainTarget(getDirection(),getTurn(),inputType);
}
}
92 changes: 39 additions & 53 deletions src/org/montclairrobotics/sprocket/drive/DriveModule.java
Original file line number Diff line number Diff line change
@@ -1,58 +1,44 @@
package org.montclairrobotics.sprocket.drive;

import edu.wpi.first.wpilibj.SpeedController;

import org.montclairrobotics.sprocket.geometry.Angle;
import org.montclairrobotics.sprocket.geometry.Inch;
import org.montclairrobotics.sprocket.geometry.Polar;
import org.montclairrobotics.sprocket.geometry.Vector;
import org.montclairrobotics.sprocket.utils.PID;

public class DriveModule extends Motor {

private Angle forceAngle;
private Vector offset;
private Inch maxSpeed;

private Vector forceVector;

public DriveModule(SpeedController motor,
Angle forceAngle, Vector offset,
SEncoder enc, PID pid, Inch maxSpeed,
boolean invert) {
super(motor, enc, pid, invert);
this.forceAngle = forceAngle;
this.offset = offset;
this.maxSpeed = maxSpeed;

this.forceVector=new Polar(maxSpeed.get(),forceAngle);
}

public DriveModule(SpeedController motor,
Angle forceAngle, Vector offset,
SEncoder enc, PID pid, Inch maxSpeed) {
this(motor, forceAngle, offset, enc, pid, maxSpeed, false);
}

public DriveModule(SpeedController motor,
Angle forceAngle, Vector offset) {
this(motor, forceAngle, offset, null, null, null, false);
}

public Angle getForceAngle() {
return forceAngle;
}

public Inch getMaxSpeed() {
return maxSpeed;
}

public Vector getOffset() {
return offset;
}

public Vector getForceVector()
{
return forceVector;
}
import org.montclairrobotics.sprocket.loop.Priority;
import org.montclairrobotics.sprocket.loop.Updatable;
import org.montclairrobotics.sprocket.loop.Updater;
import org.montclairrobotics.sprocket.pipeline.Pipeline;

public class DriveModule implements Updatable{
private Motor[] motors;
private Pipeline<Double> outputPipeline=new Pipeline<Double>(0.0);
private Vector force;
private Vector offset;
private double tgtForce;

public DriveModule(Vector force,Vector offset,Motor... motors){
this.motors=motors;
Updater.add(this, Priority.OUTPUT);
}
public Angle getTorque(Vector tgtDirection)
{
return null;

}
public void setDirectionTurn(Vector tgtDirection,Angle tgtTurn)
{

}

public void setOutputPipeline(Pipeline<Double> p)
{
this.outputPipeline=p;
}
@Override
public void update() {
tgtForce=outputPipeline.get(tgtForce);
for(Motor motor:motors)
{
motor.set(tgtForce);
}
}

}
42 changes: 0 additions & 42 deletions src/org/montclairrobotics/sprocket/drive/DrivePipeline.java

This file was deleted.

This file was deleted.

17 changes: 0 additions & 17 deletions src/org/montclairrobotics/sprocket/drive/DriveTrain.java

This file was deleted.

74 changes: 0 additions & 74 deletions src/org/montclairrobotics/sprocket/drive/DriveTrainBuilder.java

This file was deleted.

25 changes: 0 additions & 25 deletions src/org/montclairrobotics/sprocket/drive/DriveTrainInput.java

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@

public class DriveTrainTarget {

private Vector direction;
public static final DriveTrainTarget ZERO = new DriveTrainTarget(Vector.ZERO,Angle.ZERO,MotorInputType.SPEED);
private Vector direction;
private Angle turn;
private MotorInputType inputType;

Expand Down
Loading