Drives

Most FRC robots have a drive system that includes multiple motors that are controlled in various ways. Although there are lots of styles of chassis, several are common enough that Strongback provides components defined in terms of its hardware components, with methods that make it easy to drive in autonomous or teloperated modes.

TankDrive

The TankDrive component represents chassis with tank/skid-style drive system, where the wheels on one side of the robot are controlled by one or more motors, and are independent from the wheels and motors on the other side of the robot. This class provides methods to drive using arcade-style, tank-style, and cheesy-style inputs. The drive also implements Requirable so that Commands can depend upon it directly when executing.

public class TankDrive implements Requirable {

    /**
     * Creates a new DriveSystem subsystem that uses the supplied drive train and
     * no shifter. The voltage send to the drive train is limited to [-1.0,1.0].
     *
     * @param left the left motor on the drive train for the robot; may not be null
     * @param right the right motor on the drive train for the robot; may not be null
     */
    public TankDrive(Motor left, Motor right) {...}

    /**
     * Creates a new DriveSystem subsystem that uses the supplied drive train and
     * optional shifter. The voltage send to the drive train is limited to [-1.0,1.0].
     *
     * @param left the left motor on the drive train for the robot; may not be null
     * @param right the right motor on the drive train for the robot; may not be null
     * @param shifter the optional shifter used to put the transmission into high gear;
     *        may be null if there is no shifter
     */
    public TankDrive(Motor left, Motor right, Relay shifter) {...}

    /**
     * Creates a new DriveSystem subsystem that uses the supplied drive train and
     * optional shifter. The voltage send to the drive train is limited by the given
     * function.
     *
     * @param left the left motor on the drive train for the robot; may not be null
     * @param right the right motor on the drive train for the robot; may not be null
     * @param shifter the optional shifter used to put the transmission into high gear;
     *        may be null
     * @param speedLimiter the function that limits the speed sent to the drive train;
     *        if null, then a default clamping function is used to limit to the range
     *        [-1.0,1.0]
     */
    public TankDrive(Motor left, Motor right, Relay shifter,
                     DoubleToDoubleFunction speedLimiter) {...}

    /**
     * Shift the transmission into high gear. This method does nothing if the
     * drive train has no transmission shifter.
     */
    public void highGear() {...}

    /**
     * Shift the transmission into low gear. This method does nothing if the
     * drive train has no transmission shifter.
     */
    public void lowGear() {...}

    /**
     * Stop the drive train. This sets the left and right motor speeds to 0,
     * and shifts to low gear.
     */
    public void stop() {...}

    /**
     * Arcade drive implements single stick driving. This function lets you directly
     * provide joystick values from any source.
     *
     * @param driveSpeed the value to use for forwards/backwards; must be -1 to 1, inclusive
     * @param turnSpeed the value to use for the rotate right/left; must be -1 to 1, inclusive
     */
    public void arcade(double driveSpeed, double turnSpeed) {...}

    /**
     * Arcade drive implements single stick driving. This function lets you directly
     * provide joystick values from any source.
     *
     * @param driveSpeed the value to use for forwards/backwards; must be -1 to 1, inclusive
     * @param turnSpeed the value to use for the rotate right/left; must be -1 to 1, inclusive.
     *        Negative values turn right; positive values turn left.
     * @param squaredInputs if set, decreases the sensitivity at low speeds
     */
    public void arcade(double driveSpeed, double turnSpeed, boolean squaredInputs) {...}

    /**
     * Provide tank steering using the stored robot configuration. This function lets you
     * directly provide joystick values from any source.
     *
     * @param leftSpeed The value of the left stick; must be -1 to 1, inclusive
     * @param rightSpeed The value of the right stick; must be -1 to 1, inclusive
     * @param squaredInputs Setting this parameter to true decreases the sensitivity
     *        at lower speeds
     */
    public void tank(double leftSpeed, double rightSpeed, boolean squaredInputs) {...}

    /**
     * Provide tank steering using the stored robot configuration. This function
     * lets you directly provide joystick values from any source.
     *
     * @param leftSpeed The value of the left stick; must be -1 to 1, inclusive
     * @param rightSpeed The value of the right stick; must be -1 to 1, inclusive
     */
    public void tank(double leftSpeed, double rightSpeed) {...}

    /**
     * Provide "cheesy drive" steering using a steering wheel and throttle.
     * This function lets you directly provide joystick values from any source.
     *
     * @param throttle the value of the throttle; must be -1 to 1, inclusive
     * @param wheel the value of the steering wheel; must be -1 to 1, inclusive.
     *        Negative values turn right; positive values turn left.
     * @param isQuickTurn true if the quick-turn button is pressed
     */
    public void cheesy(double throttle, double wheel, boolean isQuickTurn) {...}
}

There are several constructors that take a left and right Motor, and an optional Relay for the shifter. By default all inputs will be limited between -1.0 and 1.0 , but a third contructor allows you to pass in a custom function that limits the values to a different range.

Many drive trains have multiple motors on each side, so simply use Motor.compose(…​) to create a logical single motor for each side of the robot from multiple motors. Here’s an example that uses two motors on each side:

Motor leftFront = ...
Motor leftRear = ...
Motor rightFront = ...
Motor rightRear = ...
Motor left = Motor.compose(leftFront, leftRear);
Motor right = Motor.compose(rightFront, rightRear);
TankDrive drive = new TankDrive(left, right);

The TankDrive class has highGear() and lowGear() methods that, if a Relay for the transmission is supplied in the constructor, shift the transmission between high and low gears. The stop() method stops all motors.

The TankDrive class can be controlled in several different ways:

  1. Arcade Style - Uses an arcade-style joystick: moving the joystick forward makes the robot move forward at a speed proportional to the joystick position; moving it backwards makes the robot go backward proportional to the joystick position; moving the joystick to the left turns the robot to the left at a turn speed proportional to the joystick position; and moving the joystick to the right turns the robot to the right at a turn speed proportional to the joystick position.

  2. Tank Style - Uses two joysticks (perhaps on an Xbox-style gamepad controller), where the left joystick controls the speed of the left motors, and the right joystick controls the speed of the right motors. Both joysticks are moved forward to make the robot drive forward, or moved backward to make the robot drive backward. A difference in the position of the left and right joysticks causes the robot to turn.

  3. Cheesy Drive - Inspired by Team 254, cheesy drive uses a steering wheel to turn left and right, and a separate throttle to control speed. A quick-turn parameter increases the turning speed at slower forward/reverse speeds.

The following fragment shows how to drive forward at 50% speed using the arcade style control:

drive.arcade(0.5, 0.0);

and tank style control:

drive.tank(0.5, 0.5);

and cheesy style control:

drive.cheesy(0.5, 0.0, false);

Normally the parameters are read from user input devices. For example, here’s most of a sample robot program that sets up the motors, TankDrive and speed ranges from a Logitech Attack 3D user input device connected to the Driver Station:

public class SimpleTankDriveRobot extends IterativeRobot {

    ....

    private TankDrive drive;
    private ContinuousRange driveSpeed;
    private ContinuousRange turnSpeed;

    @Override
    public void robotInit() {
        ...
        Motor left = Motor.compose(Hardware.Motors.talon(1), Hardware.Motors.talon(2));
        Motor right = Motor.compose(Hardware.Motors.talon(3), Hardware.Motors.talon(4)).invert();
        drive = new TankDrive(left, right);

        FlightStick joystick = Hardware.HumanInterfaceDevices.logitechAttack3D(1);
        driveSpeed = joystick.getPitch();
        turnSpeed = joystick.getRoll().invert();

        ...
    }

    @Override
    public void teleopPeriodic() {
        drive.arcade(driveSpeed.read(), turnSpeed.read());
    }
}

The robotInit() method does all of the initialization of the TankDrive and user input device, and it creates two ContinuousRange objects from the joystick pitch and roll axis. (Note that the turn speed is inverted based upon the sign of the joystick and that of the TankDrive.)

The teleopPeriodic() method is called many times each second, and it gets the drive speed and turn speed from the appropriate ranges and calls drive.arcade(…​) with the two speeds.

Here’s a very similar example that uses tank style inputs with an Xbox-style controller:

public class SimpleTankDriveRobot extends IterativeRobot {

    ....

    private TankDrive drive;
    private ContinuousRange leftSpeed;
    private ContinuousRange rightSpeed;

    @Override
    public void robotInit() {
        ...
        Motor left = Motor.compose(Hardware.Motors.talon(1), Hardware.Motors.talon(2));
        Motor right = Motor.compose(Hardware.Motors.talon(3), Hardware.Motors.talon(4)).invert();
        drive = new TankDrive(left, right);

        Gamepad pad = Hardware.HumanInterfaceDevices.logitechDualAction(1);
        leftSpeed = pad.getLeftY();
        rightSpeed = pad.getRightY();

        ...
    }

    @Override
    public void teleopPeriodic() {
        drive.tank(leftSpeed.read(), rightSpeed.read());
    }
}

Other than renaming the ContinuousRange fields, the bulk of the difference is in the robotInit() method and the setup of the two ContinuousRange fields.

Regardless of the style of control that is used in teleoperated mode, autonomous mode can use any of the three control methods. Simply use the methods that best match your autonomous control logic.

results matching ""

    No results matching ""