There are two options:
Download the zip file from the repo
Clone the repo (git clone https://github.com/acmerobotics/road-runner-quickstart.git)
Add the following lines to the file build.gradle
repositories {
maven {
url = 'https://maven.brott.dev/'
}
}
Also add the following lines inside of the dependencies curly braces
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
implementation "com.acmerobotics.roadrunner:core:1.0.1"
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
implementation "com.acmerobotics.dashboard:dashboard:0.5.0"
Run a Gradle Sync
Download repo and unzip or clone the repo (git clone https://github.com/acmerobotics/road-runner-quickstart.git)
Copy all the contents inside of TeamCode/src/main/java/org/firstinspires/ftc/teamcode into your repo
Update the following lines in the file MecanumDrive.java
(BEFORE) localizer = new DriveLocalizer(pose);
(AFTER) localizer = new inpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
NOTE: Make sure that the motor name values on MecanumDriva.java matches your robot configurations
NOTE: If you need to update the direction of your motors you will need to add those lines. Just search for "TODO: reverse motor directions if needed" and add your lines there.
Update the following lines in the file PinpointLocalizer.java. We do this because in the GoBilda setup we configure the odometery computer to "odo"
(BEFORE) driver = hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint");
(AFTER) driver = hardwareMap.get(GoBildaPinpointDriver.class, "odo");
The following tuning steps should take placed on tiles. We would suggest a 2 tiles width with about 8 tiles of length.
Goal: determine the value for inPerTick, this value will become that ratio between the distance traveled by you robot to the number calculated from by the encoders
Run FowardPushTest and slowly push the robot straight forward . Record what the "ticks traveled" (shown on your driver hub) and then measure the inches traveled. Make sure that you are measuring from the starting position of the back of the robot to the end position of the back of the robot.
inPerTick = (inches traveled) / (ticks traveled)
NOTE: Make sure the wheels don’t slip! If your "ticks traveled" is negative then update encoder direction for the variable initialParDirection inside of PinpointLocalizer.java
Goal: determine the value for kS, kV, these two values are to help with making sure that the robot moves smoothly
This program will increase the power on your motors by 0.1 every second till it reaches 0.9 so make sure that there is plenty of distance in front of your robot. Start the op mode and press stop as soon as the robot reaches the edge.
To see the results of this program:
Connect a laptop to your robots wifi
Go to the following link: http://192.168.43.1:8080/tuning/forward-ramp.html
Press "Latest"
A graph and the values for kS and kV should appear
Copy the values for kS and kV to the variables in MecanumDrive.java.
NOTE: Make sure that you copy kS and kV correctly as this will affect the following steps
Goal: determine the value for lateralInPerTick
This is the similar to FowardRampLogger but instead the robot is moving from right to left.
To see the results of this program:
Connect a laptop to your robots wifi
Go to the following link: http://192.168.43.1:8080/tuning/lateral-ramp.html
Press "Latest"
A graph and lateralInPerTick should appear
Copy the value for lateralInPerTick to the variable in MecanumDrive.java.
Goal: determine the value for trackWidthTicks and odometry wheel locations empirically
The robot will rotate in place after a couple seconds stop the program.
To see the results of this program:
Connect a laptop to your robots wifi
Go to the following link: http://192.168.43.1:8080/tuning/dead-wheel-angular-ramp.html
Press "Latest"
Copy the values of kS and kV and press update
Three graphs should appear (scroll down)
Copy the value for trackWidthTicks to the variable in MecanumDrive.java.
Copy the values for parYTicks and perpXTicks to the variables in PinpointLocalizer.java.
Goal: determine the value for kA
This program will make the robot drive forward and backward for DISTANCE unit (default is set to 64).
Connect a laptop to your robots wifi
Open the FTC Dashboard http://192.168.43.1:8080/dash
Run this op mode and choose all of the available variables and graph them
Your goal is to update the values of kA incrementally starting at 0.00001 until you see that the blue line (your robot) as close as possible to the red line (optimal solution). A strategy is to decrease in factors of 10 (meaning going from 0.00001 to 0.0001) and once it gets really close start using small increments.
NOTE: If your robot is driving forward and backward agressively then check that you have the correct values fro kS and kV
Goal: determine the value for axialGain,lateralGain, and headingGain
This program will do the same routine as ManualFeedforwardTuner but we will use this opportunity to tune some parameters
Connect a laptop to your robots wifi
Open the FTC Dashboard http://192.168.43.1:8080/dash
Run this op mode and choose all of the available variables and graph them
On the first run your robot should look like the following:
NOTE: The first half of the graph is the robot before kicking it and the second part of the graph is after the kick. You can see that the graph does not go back to before the kick.
You can either use the following values as a starting point or focus on one parameter set it to 1.0 and test, every time adding 1 until you get the desired output.
axialGain = 4.0
lateralGain = 3.0
headingGain = 5.0
After running multiple tests you robot and graph should look similar to what is shown below:
NOTE: Can you see the difference in the graph? After the kick the graph and robot corrects itself and goes back to its original path.