Go to Post Use sensors to collect data about the surrounding environment, then discard it and drive into walls. - Jared Russell [more]
Home
Go Back   Chief Delphi > Technical > Programming > Java
CD-Media   CD-Spy  
portal register members calendar search Today's Posts Mark Forums Read FAQ rules

 
Reply
Thread Tools Rate Thread Display Modes
  #1   Spotlight this post!  
Unread 11-02-2014, 16:42
SoftwareRachel's Avatar
SoftwareRachel SoftwareRachel is offline
Registered User
FRC #4505
 
Join Date: Feb 2014
Location: Maryland
Posts: 12
SoftwareRachel is an unknown quantity at this point
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.
Reply With Quote
  #2   Spotlight this post!  
Unread 11-02-2014, 16:47
Ether's Avatar
Ether Ether is offline
systems engineer (retired)
no team
 
Join Date: Nov 2009
Rookie Year: 1969
Location: US
Posts: 8,102
Ether has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond reputeEther has a reputation beyond repute
Re: Delay Problem

Quote:
Originally Posted by SoftwareRachel View Post
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.
All the code in TeleOp must execute in less than 20ms so that it can be called again when the next DS packet arrives.

You can use a state machine, start a new thread, or use the CommandBased framework.


Reply With Quote
  #3   Spotlight this post!  
Unread 11-02-2014, 16:51
notmattlythgoe's Avatar
notmattlythgoe notmattlythgoe is online now
Flywheel Police
AKA: Matthew Lythgoe
FRC #2363 (Triple Helix)
Team Role: Mentor
 
Join Date: Feb 2010
Rookie Year: 2009
Location: Newport News, VA
Posts: 1,728
notmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond repute
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.
Reply With Quote
  #4   Spotlight this post!  
Unread 11-02-2014, 18:51
SoftwareRachel's Avatar
SoftwareRachel SoftwareRachel is offline
Registered User
FRC #4505
 
Join Date: Feb 2014
Location: Maryland
Posts: 12
SoftwareRachel is an unknown quantity at this point
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.
Reply With Quote
  #5   Spotlight this post!  
Unread 12-02-2014, 06:25
pblankenbaker pblankenbaker is offline
Registered User
FRC #0868
 
Join Date: Feb 2012
Location: Carmel, IN, USA
Posts: 108
pblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of light
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();
    }
}
NOTE: The code above uses the timeSinceIntialized() method to determine when to turn the motors off (this does not block). This approach also "cleanly" ends the command.

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:
  • Set up and start the PID controller in the initialize() method.
  • Disable the PID controller and stop the motors in the end() method.
  • Update the isFinished() method to return true if the time out period was reached OR the PID had reached its set point.

Hope that helps,
Paul
Reply With Quote
  #6   Spotlight this post!  
Unread 12-02-2014, 11:30
aziobro aziobro is offline
Registered User
FRC #4475 (Terrier Byte Bots)
Team Role: Leadership
 
Join Date: Nov 2008
Rookie Year: 2009
Location: Newark,NJ
Posts: 7
aziobro will become famous soon enough
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.
Reply With Quote
  #7   Spotlight this post!  
Unread 12-02-2014, 13:32
pblankenbaker pblankenbaker is offline
Registered User
FRC #0868
 
Join Date: Feb 2012
Location: Carmel, IN, USA
Posts: 108
pblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of lightpblankenbaker is a glorious beacon of light
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.
Reply With Quote
  #8   Spotlight this post!  
Unread 12-02-2014, 14:06
krieck's Avatar
krieck krieck is offline
Registered User
AKA: Keith
FRC #2846 (Firebears)
Team Role: Mentor
 
Join Date: Jan 2012
Rookie Year: 2012
Location: Minnesota
Posts: 49
krieck is an unknown quantity at this point
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();
    }
    
}
Reply With Quote
  #9   Spotlight this post!  
Unread 12-02-2014, 14:16
notmattlythgoe's Avatar
notmattlythgoe notmattlythgoe is online now
Flywheel Police
AKA: Matthew Lythgoe
FRC #2363 (Triple Helix)
Team Role: Mentor
 
Join Date: Feb 2010
Rookie Year: 2009
Location: Newport News, VA
Posts: 1,728
notmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond reputenotmattlythgoe has a reputation beyond repute
Re: Delay Problem

Quote:
Originally Posted by krieck View Post
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();
    }
    
}
We just discovered the timeout ability for commands this year and I keep forgetting that you can do it. We're using it to timeout our hot goal processing in case we don't find a target we don't end up sitting for the entire autonomous period.
Reply With Quote
Reply


Thread Tools
Display Modes Rate This Thread
Rate This Thread:

Posting Rules
You may not post new threads
You may not post replies
You may not post attachments
You may not edit your posts

vB code is On
Smilies are On
[IMG] code is On
HTML code is Off
Forum Jump


All times are GMT -5. The time now is 12:50.

The Chief Delphi Forums are sponsored by Innovation First International, Inc.


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