Chief Delphi

Chief Delphi (http://www.chiefdelphi.com/forums/index.php)
-   Java (http://www.chiefdelphi.com/forums/forumdisplay.php?f=184)
-   -   whileHeld() Motor Program Issue (http://www.chiefdelphi.com/forums/showthread.php?t=125671)

LFRobotics 02-02-2014 10:42

whileHeld() Motor Program Issue
 
Okay - I am programming a command based java and wrote a couple of commands defined by a subsystem called ForkMotor. One command was supposed to move a motor forward(1) while a button was pressed. The other was supposed to move a motor backwards(-1) while a button is pressed. When I hold the button down that is supposed to move it forward the motor glitches off and on but does stop when I let go - the motor is fine I tested it. The button that SHOULD turn it in the other direction doesn't work at all. If anyone knows how to fix this that would be AWESOME.

Here it is:

Subsystem(called ForkMotor):


Quote:

package edu.wpi.first.LFRobot2014.subsystems;

import edu.wpi.first.LFRobot2014.RobotMap;
import edu.wpi.first.wpilibj.Jaguar;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.command.Subsystem;

/**
*
* @author FrankyMonezz
*/
public class ForkMotor extends Subsystem {
// Put methods for controlling this subsystem
// here. Call these from Commands.
SpeedController motor = new Jaguar(RobotMap.ForkMotorPort);

public void initDefaultCommand() {
// Set the default command for a subsystem here.
//setDefaultCommand(new MySpecialCommand());
}

public void up() {
motor.set(1);
}

public void down() {
motor.set(-1);
}

public void stop(){
motor.set(0);
}
}
First Command(to move it forward -- called LiftForks):

Quote:

package edu.wpi.first.LFRobot2014.commands;


/**
*
* @author FrankyMonezz
*/
public class LiftForks extends CommandBase {

public LiftForks() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(forkmotor);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
forkmotor.up();
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}

Second Command(to move it in reverse -- called LowerForks):


Quote:

package edu.wpi.first.LFRobot2014.commands;

/**
*
* @author FrankyMonezz
*/
public class LowerForks extends CommandBase {

public LowerForks() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(forkmotor);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
forkmotor.down();
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
Port Assignment(called ForkMotorPort):

Quote:

public static final int
leftMotorPort = 1,
rightMotorPort = 2,
ArmMotorPort = 3,
ForkMotorPort = 4;
CommandBase(called ForkMotor):

Quote:

public abstract class CommandBase extends Command {

public static OI oi;
// Create a single static instance of all of your subsystems
public static ForkMotor forkmotor = new ForkMotor();
public static ArmMotor armmotor = new ArmMotor();
public static Chassis chassis = new Chassis();
public static LaunchServo launchservo = new LaunchServo();
Button Assignments(LiftForks - moves it forward(1) -- LowerForks - moves it in reverse(-1):


Quote:

public Joystick
rightStick,
leftStick;

private final Button ForksDown, ForksUp, prepball, prepball2, motor1, motor2; //add Auto



public OI() {

rightStick = new Joystick(RobotMap.rightJoystickPort);
leftStick = new Joystick(RobotMap.leftJoystickPort);
ForksDown = new JoystickButton(rightStick, 5);
ForksUp = new JoystickButton(rightStick, 4);
prepball = new JoystickButton(leftStick, 4);
prepball2 = new JoystickButton(leftStick, 5);
motor1 = new JoystickButton(rightStick, 2);
motor2 = new JoystickButton(rightStick, 3);

//Auto = new JoystickButton(leftStick, 4);

ForksUp.whileHeld(new LiftForks());
ForksDown.whileHeld(new LowerForks());
prepball.whenPressed(new PrepBall());
prepball2.whenPressed(new PrepBall2());
motor1.whenPressed(new ArmLauncher());
motor2.whenPressed(new ReleaseTension());
//Auto.whenPressed(new AutoCommandGroup());
}

public Joystick getRightStick() {
return rightStick;
}

public Joystick getLeftStick() {
return leftStick;
}

}
ANY help WILL be appreciated - THANKS!

otherguy 02-02-2014 23:20

Re: whileHeld() Motor Program Issue
 
Check out the javadoc for the whileHeld method. It might not be doing what you expect.

whileHeld will repeatedly call the command's start method (50 times a second).
The start method will add the command to the scheduler. In the command based project, the scheduler is the bit of code that is responsible for stepping all active commands through their steps of execution [initialize(), execute(), isfinished(), end()].

The comment on the start() method is worth reading:
Quote:

Note that the command will eventually start, however it will not necessarily do so immediately, and may in fact be canceled before initialize is even called.
Instead of using the whileHeld method to keep a motor moving while the button pressed, I would instead suggest using the whenPressed and whenReleased methods to kick off a command once for the pressed and release events. Since your commands are set up to never finish executing, this single instance of the command that is scheduled will continue to run until another command comes along that requires the subsystem specified.

Code:

ForksUp.whenPressed(new LiftForks());
ForksUp.whenReleased(new StopForks());
ForksDown.whenPressed(new LowerForks());
ForksDown.whenReleased(new StopForks());

Note that StopForks is a new command that you will need to make that should call the stop() method for the ForkMotor subsystem. The StopForks method may also be a good one to specify as the default command for the subsystem (see the initDefaultCommand() method comments). Generally you don't want things moving around.

Other than the use of whileHeld, I don't see any other glaring errors in your code.

LFRobotics 04-02-2014 21:31

Re: whileHeld() Motor Program Issue
 
Okay - THANKS a ton!

fovea1959 09-02-2014 10:30

Re: whileHeld() Motor Program Issue
 
whileHeld() works as advertised, you just need to remember to shut down things in end() and interrupted()...

Our experience last summer was whileHeld called init() once, (execute(), getFinished()) repeatedly, and interrupted() is called when the button is released. We used whileHeld reliably with commands like this (note that we stop the motor from end() and interrupted().

We would see multiple init() if several whileHelds fired off commands that required the same subsystem(s) and those buttons were held at the same time. I don't remember the exact details.

Code:

package org.usfirst.frc3620.FRC36202013RobotRedo.commands;

import edu.wpi.first.wpilibj.command.Command;
import org.usfirst.frc3620.FRC36202013RobotRedo.Robot;

/**
*
*/
public class FlipperBackwardCommand extends Command {

    public FlipperBackwardCommand() {
        // Use requires() here to declare subsystem dependencies
        // eg. requires(chassis);

        // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES
        requires(Robot.flipperSubsystem);
        // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES
    }

    // Called just before this Command runs the first time
    protected void initialize() {
    }

    // Called repeatedly when this Command is scheduled to run
    protected void execute() {
        Robot.flipperSubsystem.flipperBackward();
    }

    // Make this return true when this Command no longer needs to run execute()
    protected boolean isFinished() {
        return false;
    }

    // Called once after isFinished returns true
    protected void end() {
        Robot.flipperSubsystem.flipperStop();
    }

    // Called when another command which requires one or more of the same
    // subsystems is scheduled to run
    protected void interrupted() {
        end();
    }
}


otherguy 09-02-2014 20:28

Re: whileHeld() Motor Program Issue
 
I went through the code more closely than last time...

JoystickButton inherits whileHeld from Button.
Button extends Trigger.
whileHeld calls Trigger's whileActive method

From Javadoc:
Code:

whileActive

public void whileActive(Command command)
Constantly starts the given command while the button is held. Command.start() will be called repeatedly while the trigger is active, and will be canceled when the trigger becomes inactive.

Parameters:
command - the command to start

That's as far as I went. I assumed that calling start repeatedly on a command would cause it to cancel a previous running instance of the command. What it does do:

Command.start() adds the command to a vector of command that should be added to the list of commands that the scheduler will process.

Here's the catch, the scheduler doesn't do anything with the command if the command is already in the list. See line 145.

So I agree. whileHeld should work as advertised. I know that I've had trouble with it in the past, and have always implemented commands as I outlined above. Maybe the problems I had with whileHeld were actually with something else, I haven't gone back to investigate.


All times are GMT -5. The time now is 09:30.

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