|
|
|
![]() |
|
|||||||
|
||||||||
![]() |
|
|
Thread Tools | Rate Thread | Display Modes |
|
|
|
#1
|
||||
|
||||
|
Delay Problem
Hello, My team is trying to run a CIM motor connected to a victor as a part of our shooter. We need to run it for a specific (short) length of time, but when we use either a Timer.delay or a while loop in a command in the subsystem, the other motors running pause. Does anyone have any solutions to this? Thank you.
|
|
#2
|
||||
|
||||
|
Re: Delay Problem
Quote:
You can use a state machine, start a new thread, or use the CommandBased framework. |
|
#3
|
|||||
|
|||||
|
Re: Delay Problem
I'm assuming you're using the command based approach form the way you have this phrased. I'd take a look at the CommandGroup class and see if that will solve your problem.
|
|
#4
|
||||
|
||||
|
Re: Delay Problem
Thank you for your responses. We tried many of these fixes without much success. We ended up running our drive train in the method, and while it's not the most elegant solution, it works. Thank you for your help.
|
|
#5
|
|||
|
|||
|
Re: Delay Problem
Here is an example of a command which drives the robot for a particular amount of time using the command based framework. When using the command based approach, you never want to "block" (don't use Timer.delay() in your code). Instead you look for timeout conditions.
Code:
package com.techhounds.robot.commands.drive;
import com.techhounds.robot.subsystems.DriveSubsystem;
import com.techhounds.robot.subsystems.RobotParts;
import edu.wpi.first.wpilibj.command.Command;
public final class DriveByPower extends Command {
private final double _LeftPower;
private final double _RightPower;
private final double _RunTime;
private final DriveSubsystem _Drive;
public DriveByPower(double leftPower, double rightPower, double runTime) {
super("Drive (" + leftPower + ", " + rightPower + ", " + runTime + ")");
// Save settings to apply/use when the command is started and running
_LeftPower = leftPower;
_RightPower = rightPower;
_RunTime = runTime;
// Indicate what subsystems are required
_Drive = RobotParts.getInstance().getDrive();
requires(_Drive);
// Allow other commands that need to use the drive system to take control
setInterruptible(true);
}
protected void initialize() {
// Turn on the motors when the command is started
_Drive.driveTank(_LeftPower, _RightPower);
}
protected boolean isFinished() {
// Done once the run time period has been reached
return (timeSinceInitialized() >= _RunTime);
}
protected void execute() {
// Nothing to do here (motors should still be running)
}
protected void end() {
// Make sure we turn off the motors when done
_Drive.driveTank(0, 0);
}
protected void interrupted() {
end();
}
}
There is a setTimeout(secs) method available to all commands. I would recommend avoiding that option as it interrupts the command (as opposed to letting the command terminate normally as shown in the above example). It will probably yield the same results when running the command by itself, but has caused us issues when grouping commands (command groups seem to prefer commands that run cleanly as opposed to those that are interrupted). A PID based drive command would be similar, but would:
Hope that helps, Paul |
|
#6
|
|||
|
|||
|
Re: Delay Problem
Move a copy of your code that is in initialize into the execute method.
This will keep it updating every 20ms so that the drive does not time out. |
|
#7
|
|||
|
|||
|
Re: Delay Problem
Good point on moving the code that sets the motor powers inside the execute() method to avoid the time out issue if you run with the motor safety feature enabled.
Our team has gotten to the point that the watch dog timers seem to be more burdensome than beneficial. We have gotten in the (bad) habit of turning off the motor safety feature. This means we don't have to worry about the time out issue and can leave the code as shown in the example. **However** Some of our new programmers had a run away robot situation the other day - so maybe we should think about enabling it again. |
|
#8
|
||||
|
||||
|
Re: Delay Problem
The Command class already has a built-in timeout function. You just set it up in the initialize() method and then stop your command in isFinished:
Code:
package org.usfirst.frcxyz.commands;
import edu.wpi.first.wpilibj.command.Command;
public class DriveTimeCommand extends Command {
double timeToDriveInSeconds = 2.5;
public DriveTimeCommand() {
requires(Robot.chassis);
}
protected void initialize() {
setTimeout(timeToDriveInSeconds);
}
protected void execute() {
Robot.chassis.arcadeDrive(1.0, 0.0);
}
protected boolean isFinished() {
return isTimedOut();
}
protected void end() {
Robot.chassis.arcadeDrive(0.0, 0.0);
}
protected void interrupted() {
end();
}
}
|
|
#9
|
|||||
|
|||||
|
Re: Delay Problem
Quote:
|
![]() |
| Thread Tools | |
| Display Modes | Rate This Thread |
|
|