Preseason Lesson2

From 1511Wookiee
Revision as of 14:09, 30 December 2021 by Heydowns (talk | contribs)
(diff) ← Older revision | Latest revision (diff) | Newer revision → (diff)
Jump to navigationJump to search

Goal

In this lesson we read inputs from a joystick/gamepad/controller on the Driver Station and that input to make decisions in our program to control the same motor from lesson 1 in a more sophisticated manner.

Detailed Introduction

  • Before doing this lesson you should have completed Lesson 1 and have the code for that as a starting point.
  • In this lesson we will use more of the base WPILib library than we did in the past. Remember that the documentation for WPILib is linked on the main programming page in our wiki!
  • This lesson will begin to use control statements in our code - we will make use of C++ if/else statements

Detailed Goals

  • You will again be controlling Motor 5
  • We will be reading from a gamepad connected to the driver station. The gamepad will be assigned an address identifier of 0
  • The motor should turn at 1/4 speed only when the button labelled 1 is pressed and when the left stick is moved forward or backward
  • The direction the control stick is pressed should control the motor direction (forward or backward)!
  • The movement of the control stick should contain a deadzone near center that prevents the motor from moving if the amount the stick is pressed is very small (less than 1/3 pressed)

Guided Help

Create a Joystick Object

To read the input from the controller, we will need to create a Joystick object in our main robot class. Here is a direct link to the documentation for the Joystick class. While the class is called 'Joystick', it can also be used to read from controllers/game pads connected to the Driver Station.

  • The process for creating our Joystick object is exactly the same as the process used to make our motor controller object in Lesson 1, so less instructions will be given here! You can always go back to lesson 1 instructions to refresh your memory if needed!
  • The Joystick class is declared in a header file named Joystick.h - the full path you need to use it is frc/Joystick.h
  • The Joystick class is in the frc namespace. You can refer to it by its full name 'frc::Joystick' or you can use simply 'Joystick' if you tell your program to use the entire 'frc' namespace.
  • Using the above information, create a Joystick object in your main robot class. You can choose any name you like for the object but the rest of the guided help below will use the name controller

Reading the Button Input from the Joystick

We will need to read the input value for first button of the controller from our Joystick object we've just created. If you look at the Joystick class documentation you can see many available methods. We will use two of these to read the button and capture the result of the method calls in local variables. We will again be working inside TeleopPeriodic function of our main robot class.

Look at the documentation for the Joystick class - you will see that it contains a method named 'GetRawButton()' which is what we will use to see if the button is being pressed. The method is a function which takes one input argument, an int (short for integer) that represents the button number to read, and returns a bool (short for boolean) which represents if the button is pressed (true) at that moment or not (false). This section will guide you on calling this function and storing the result in a local variable.

  • At the top of TeleopPeriodic, let's create a new local variable that will hold the state of the inputs we are interested in.
    • A local variable is a variable that is local to a single block of code. In this case, the block of code the variable is local to is the TeleopPeriodic() function. A local variable declaration is very similar to how we declared objects (like the motor or joystick) in our class, except that we will do them locally in the function: we state the type of the variable followed by a name that will be used to refer to it.
    • Let's start with a variable to hold the value of the controller button being pressed or not. Add the following line to the top of TeleopPeriodic():
      bool buttonOnePressed = false;
    • This creates a local variable named 'buttonOnePressed' that is of type bool. 'bool' is short for 'boolean', which is a type that can have the value true or false. We immediately give the new variable the value false. If we don't give it a value, the value is undefined (random value).
  • Now let's call the GetRawButton() method to get the state of the button and store the result in our new local variable:
    • Add this line below the previously added one:
      buttonOnePressed  = controller.GetRawButton(1);
    • This calls the GetRawButton() method of our controller object, returning true or false depending on if the button is pressed at the time, and stores that result in our 'buttonOnePressed' variable.

Deciding to run the motor or not: Making Decisions in Code

Now that our local variable contains the current "pressed or not" state of the controller, we can use it to decide to run the motor or not. Control of flow in a program is like making decisions and acting on them. One of the more simple, but still very powerful, ways to control flow in a program is with the if/else statement. If/else works just like it does in common English!

In simple English, what we want to accomplish is: if the controller button is pressed, then run the motor at 1/4 forward speed. Else, (otherwise) do not run the motor.

Now we will translate this to code:

  • Add the following below where we called GetRawButton() in the previous steps:
    if (buttonOnePressed) {
    motor.Set(ControlMode::PercentOutput, 0.25);
    } else {
    motor.Set(ControlMode::PercentOutput, 0);
    }
    • Here, the part in parenthesis after if is our condition, or decision to make. If the condition is true, any code we put between the braces {} will be run. If it is not true, then the code in the braces after the else statement is run instead.
    • You can also have an if () with only a block of statements to run when true and leave off the else part if you do not need it.
    • Because our buttonOnePressed variable is itself a boolean value, we can simply use it alone as our condition. The next section will introduce other ways to use conditions in an if statement.
    • You will want to remove the line from Lesson 1 that ran the motor unconditionally if you have not yet done so.
  • Before proceeding to the next section, you may wish to try running this on the test board.

Controlling Direction based on Controller Left Stick Input

We will now add to what you already have to run the motor forward or reverse at 1/4 speed depending on the movement of the left control stick. Less help will be given for this part! Use what you learned in the previous section to complete this part!

  1. Look at the documentation for the Joystick class again - you will see that it contains a method named 'GetRawAxis()' which you can use to determine if the left stick is being pressed forward or backward and how far it is being pressed.
    • This takes one input argument, similar to how GetRawButton() did, which is an address identifier number that identifies which axis you want to read in. Use the Driver Station's USB input tab to see what the address/id number is for the axis you want to read (left stick, Y axis)
    • This returns a double value. A double can represents a number like integer (int), but unlike int, a double can include a fractional part. The 0.25 we have been using to specify 1/4 motor power is one example of a double!
    • The double value returned for the controller stick position is normalized as a fraction between -1.0 and 1.0. -1.0 means the lowest possible extreme, 1.0 means the highest possible extreme, 0 means "centered", and the values in between scale to represent all partially pressed positions
    • Note that it is rare to get a controller that reads exactly 0 when centered! This is due to how the device electronics work! So you will want what is known as a deadzone - this is the amount above and below zero where we will treat the stick as centered still! The exact value you would use for a given controller's axis has to be measured by using it, but for this example we will use 1/3 of the possible travel as a safety deadzone.
  2. Begin by declaring a new local variable to hold the result of calling GetRawAxis() on the controller. You can name it whatever you like, but the rest of these instructions will refer to this variable by the name leftYAxis
  3. Call GetRawAxis() on the correct axis number and store the result in your new local variable
  4. Now you will use your leftYAxis variable's value to decide which direction to run the motor. You can do this with numeric comparisons inside your if conditionals. This will guide you through the forward direction:
    • Remember we only want to be doing any of the next items when the button is pressed, so be sure you are adding this code in the right place in your existing code!
    • Recall also that we want to treat the first 1/3rd of the stick movement as a deadzone!
    • To do this, we will add a second 'if' statement to see if the controller left stick has a value above our deadzone. This will replace your existing line that runs the motor:
      if (leftYAxis > 0.33) {
      motor.Set(ControlMode::PercentOutput, 0.25);
      }
    • This says "if the left Y axis is more than 1/3 pressed, turn the motor on at 1/4 speed forward"
    • Take note! This lacks code to handle other possible values of leftYAxis!
  5. Now, using the above information as a guide, add additional code to handle the other possible values of leftYAxis:
    • You need to handle running the motor in reverse at 1/4 speed if the stick is moved more than 1/3 of the way down. Use a negative value for the speed when calling Set() to run the motor in reverse.
    • You need to handle stopping the motor if the stick is "close to" the center

Testing

When you have your code ready, make sure it builds, then coordinate with your classmates/the instructor to have time on the test board to test it. Refer to lesson 1 if you need help with building or deploying.

When testing, verify the following:

  1. When enabled and the controller is not touched, the motor should not move.
  2. Pressing just button 1 on the controller should not cause the motor to move
  3. Just moving the left stick up or down on the controller should not cause the motor to move
  4. The motor should go forward when holding down button 1 and moving the stick up. Verify the right direction on the motor by looking at the lights on the motor controller - they should be green for forward and red for backwards. Similarly the motor should go backward when holding button 1 and moving the stick down.
  5. If the motor was not spinning the right way, look carefully at why and correct your program!
  6. While the motor is moving in the above tests, release the button or the stick and verify the motor stops

Solution

This is one possible solution! There are many ways to accomplish the goal(s) - this is just one way!

robot.h

// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

#pragma once

#include <frc/TimedRobot.h>
#include <ctre/Phoenix.h>
#include <frc/Joystick.h>

using namespace ctre::phoenix::motorcontrol::can;
using namespace frc;

class Robot : public frc::TimedRobot {
  TalonSRX motor{5};
  Joystick controller{0};

 public:
  void RobotInit() override;
  void RobotPeriodic() override;

  void AutonomousInit() override;
  void AutonomousPeriodic() override;

  void TeleopInit() override;
  void TeleopPeriodic() override;

  void DisabledInit() override;
  void DisabledPeriodic() override;

  void TestInit() override;
  void TestPeriodic() override;
};


robot.cpp

// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

#include "Robot.h"

void Robot::RobotInit() {}
void Robot::RobotPeriodic() {}

void Robot::AutonomousInit() {}
void Robot::AutonomousPeriodic() {}

void Robot::TeleopInit() {}
void Robot::TeleopPeriodic() {
  bool buttonOnePressed = false;
  buttonOnePressed = controller.GetRawButton(1);
  double leftYAxis = 0;
  // controller y-axis is inverted! multiply by -1 to correct direction
  leftYAxis = -1 * controller.GetRawAxis(1);

  if (buttonOnePressed) {
    if (leftYAxis > 0.33) {
      motor.Set(ControlMode::PercentOutput, 0.25);
    } else if (leftYAxis < -0.33) {
      motor.Set(ControlMode::PercentOutput, -0.25);
    } else {
      motor.Set(ControlMode::PercentOutput, 0);
    }
  } else {
    motor.Set(ControlMode::PercentOutput, 0);
  }
}

void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}

void Robot::TestInit() {}
void Robot::TestPeriodic() {}

#ifndef RUNNING_FRC_TESTS
int main() {
  return frc::StartRobot<Robot>();
}
#endif