Chief Delphi

Chief Delphi (http://www.chiefdelphi.com/forums/index.php)
-   Java (http://www.chiefdelphi.com/forums/forumdisplay.php?f=184)
-   -   Invert Motors in Java (http://www.chiefdelphi.com/forums/showthread.php?t=121484)

Zaque 09-11-2013 12:27

Invert Motors in Java
 
Hello,

We are switching from LabVIEW to Java for the coming build season, and we are currently rewriting our 2013 code in java. We have everything working except for the driving. In the LabVIEW program we had, our front and rear left motors inverted. I have looked at other posts using RobotDrive.setInvertedMotor, but I have not been able to get the program to accept it. My code is attached:

/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2008. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/

package edu.wpi.first.wpilibj.templates;


import edu.wpi.first.wpilibj.SimpleRobot;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.AnalogChannel;
import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.Timer;
/**
* The VM is configured to automatically run this class, and to call the
* functions corresponding to each mode, as described in the SimpleRobot
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the manifest file in the resource
* directory.
*/
public class RobotTemplate extends SimpleRobot {
Victor frontLeft = new Victor(1);
Victor rearLeft = new Victor(3);
Victor frontRight = new Victor(2);
Victor rearRight = new Victor(4);
/**frontLeft,rearLeft,frontRight,rearRight**/
RobotDrive chassis = new RobotDrive(frontLeft,rearLeft,frontRight,rearRight );
chassis.setInvertedMotor(RobotDrive.frontLeft, true);
chassis.setInvertedMotor(RobotDrive.rearLeft, true);

/**pressureSwitchChannel, compressorRelayChannel**/
Compressor compressor = new Compressor(1, 1);
/**channel**/
DoubleSolenoid right = new DoubleSolenoid(2, 1);
DoubleSolenoid left = new DoubleSolenoid(4, 3);
/**channel**/
AnalogChannel pot = new AnalogChannel(1,1);
Victor shooter = new Victor(8);
Victor angle = new Victor(10);
Victor loader = new Victor(9);
Joystick driver = new Joystick(1);
Joystick operator = new Joystick (2);
double v;
int i = 0;
boolean lastPress = false;
boolean currentPress = false;
boolean shooterState = false;
boolean lastPress2 = false;
boolean currentPress2 = false;
boolean solenoidState = false;

public RobotTemplate() {
compressor.start();
}


public void autonomous() {
chassis.setSafetyEnabled(false);
shooter.set(100);
v = pot.getVoltage();
/**set angle**/
while(v < 1.43){
angle.set(1);
v = pot.getVoltage();
}
angle.set(0);
/**fire**/
while(i<6){
Timer.delay(0.5);
loader.set(100);
Timer.delay(0.25);
loader.set(0);
i++;
}
shooter.set(0);
}

/**
* This function is called once each time the robot enters operator control.
*/
public void operatorControl() {
chassis.setSafetyEnabled(true);
while(isOperatorControl() && isEnabled()){
/**drive code**/
chassis.arcadeDrive(driver.getRawAxis(1), driver.getRawAxis(4));
/**hanger code**/
lastPress2 = currentPress2;
currentPress2 = driver.getRawButton(9);
if(currentPress2 && !lastPress2){
if(solenoidState){
left.set(DoubleSolenoid.Value.kForward);
right.set(DoubleSolenoid.Value.kForward);
solenoidState = false;
}else{
left.set(DoubleSolenoid.Value.kReverse);
right.set(DoubleSolenoid.Value.kReverse);
solenoidState = true;
}
}
/**shooter toggle code**/
lastPress = currentPress;
currentPress = operator.getRawButton(2);
if(currentPress && !lastPress){
if(shooterState){
shooter.set(0);
shooterState = false;
}else{
shooter.set(1);
shooterState = true;
}
}
/**loader code**/
if(operator.getRawButton(5)){
loader.set(1);
}else{
loader.set(0);
}

/**angle code**/
if(operator.getRawButton(1)){
angle.set(operator.getRawAxis(2));
}else{
angle.set(0);
}

Timer.delay(0.01);
}
}

/**
* This function is called once each time the robot enters test mode.
*/
public void test() {

}
}

Domenic Rodriguez 09-11-2013 13:06

Re: Invert Motors in Java
 
The RobotDrive#setInvertedMotor() method takes a RobotDrive.MotorType object as the first parameter instead of a reference to the actual motor. Try using this:

Code:

...
chassis.setInvertedMotor(RobotDrive.MotorType.kFrontLeft, true);
chassis.setInvertedMotor(RobotDrive.MotorType.kRearLeft, true);
...

Also, don't forget that the joysticks treat forward motion along the X axis as a negative value, whereas the RobotDrive treats a positive value as forwards movement (I think; could someone else confirm this? It may depend on your setup). You may want to negate your X axis reading as well.

Zaque 09-11-2013 13:20

Re: Invert Motors in Java
 
When I put that in the code, I get the error:

package chassis does not exist

<identifier> expected

cannot find symbol
symbol: class kFrontLeft
location: class MotorType

<identifier> expected

illegal start of type

Domenic Rodriguez 09-11-2013 13:50

Re: Invert Motors in Java
 
Make sure those two lines are inside either the robotInit() method or the constructor

Code:

public void robotInit() {
    chassis.setInvertedMotor(RobotDrive.MotorType.kFrontLeft, true);
    chassis.setInvertedMotor(RobotDrive.MotorType.kRearLeft, true);
}

or
Code:

...
public RobotTemplate() {
    compressor.start();
    chassis.setInvertedMotor(RobotDrive.MotorType.kFrontLeft, true);
    chassis.setInvertedMotor(RobotDrive.MotorType.kRearLeft, true);
}
...


Zaque 09-11-2013 15:14

Re: Invert Motors in Java
 
That solved it. Thanks for your help.


All times are GMT -5. The time now is 10:44.

Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi