Git Product home page Git Product logo

thirdcoast's Introduction

Stryke Force Third Coast Java Libraries

This project consists of three libraries that are used by Team 2767 Stryke Force.

  • Swerve Drive - software control of Third Coast swerve drive modules. This code should generally work with swerve drives that use CTRE motor controllers and a CTRE magnetic encoder for azimuth position.
  • Telemetry - provide real-time streaming telemetry information from a robot. Used with our Grapher LabView strip-chart recorder.
  • Health Check - configure automated motor health checks for use by pit crew during competitions.

Other Stryke Force engineering resources are at strykeforce.org.

Installation

The Third Coast vendordeps file is at: http://packages.strykeforce.org/thirdcoast.json

To install, use Install new libraries (online) in VS Code or download manually to your project vendordeps directory.

$ ./gradlew vendordep --url=http://packages.strykeforce.org/thirdcoast.json

Swerve Drive

We have wrapped the FRC WPILib Swerve Drive kinematics and odometry classes to work easily with our swerve module design and to facilitate use of the rest of the Third Coast libraries.

For example, here is how you can configure our swerve drive.

public class SwerveDriveSubsystem extends SubsystemBase {

    private final SwerveDrive swerveDrive;

    public SwerveDriveSubsystem() { // Pretend to set up a swerve drive

        var moduleBuilder =
                new TalonSwerveModule.Builder()
                        .driveGearRatio(DriveConstants.kDriveGearRatio)
                        .wheelDiameterInches(DriveConstants.kWheelDiameterInches)
                        .driveMaximumMetersPerSecond(DriveConstants.kMaxSpeedMetersPerSecond);

        TalonSwerveModule[] swerveModules = new TalonSwerveModule[4];
        Translation2d[] wheelLocations = DriveConstants.getWheelLocationMeters();

        // initialize the swerve modules
        for (int i = 0; i < 4; i++) {
            var azimuthTalon = new TalonSRX(i);
            // configure azimuth Phoenix API settings...
            var driveTalon = new TalonFX(i + 10);
            // configure drive Phoenix API settings...

            swerveModules[i] =
                    moduleBuilder
                            .azimuthTalon(azimuthTalon)
                            .driveTalon(driveTalon)
                            .wheelLocationMeters(wheelLocations[i])
                            .build();

            swerveModules[i].loadAndSetAzimuthZeroReference();
        }

        // initialize the swerve drive with configured swerve modules
        swerveDrive = new SwerveDrive(swerveModules);
    }
}

In the simplest case, you can control this configured SwerveDrive in open-loop, for example during tele-operation.

public class SwerveDriveSubsystem extends SubsystemBase {
    private final SwerveDrive swerveDrive;

    // ...

    public void drive(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, boolean isFieldOriented) {
        swerveDrive.drive(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond, isFieldOriented);
    }
}

Telemetry

Our Telemetry library is used to instrument subsystems and stream measurements to our Grapher LabView strip-chart recorder. We find it invaluable during the season for many tasks, not the least of which is motor controller closed-loop tuning. During motor controller closed-loop tuning we often will stream telemetry while manually controlling the motors using our tct application.

Continuing on with our example from above, to instrument the SwerveDriveSubsystem class we subclass our abstract MeasureableSubsystem instead of SubsystemBase and then implement the getMeasures() method.

public class SwerveDriveSubsystem extends MeasurableSubsystem {
    private final SwerveDrive swerveDrive;
    // ...

    @Override
    public Set<Measure> getMeasures() {
        return Set.of(
                new Measure("Gyro Rotation2D(deg)", () -> swerveDrive.getHeading().getDegrees()),
                new Measure("Odometry X", () -> swerveDrive.getPoseMeters().getX()),
                new Measure("Odometry Y", () -> swerveDrive.getPoseMeters().getY()),
                // other measurements...
        );
    }
}

Each of the Measure objects supplied from getMeasures() are created with a name, optional description, and a DoubleSupplier (typically a lambda expression) to provide the measured data.

During robot start-up, we register the instrumented subsystems with the Telemetry library. When you connect to the robot using the Grapher application, you are presented with these subsystems and their measurements as options to view in the strip-chart.

public class RobotContainer {
    private final SwerveDriveSubsystem swerveDriveSubsystem;
    private final TelemetryService telemetryService = new TelemetryService(TelemetryController::new);

    public RobotContainer() {
        swerveDriveSubsystem.registerWith(telemetryService);
        // ...
    }
}

Health Check

This system provides our pit team with the ability to define a set of pre-defined motor health checks that can be run with the press of a button. It is intended for use with subsystems that contain Talon motor controllers.

Subsystems that contain motors to be health checked are annotated with @HealthCheck and optionally, annotations that define the health check in more detail. There are three possible ways to configure a talon for testing:

  • @Timed - runs the motor at the specified output for the specified amount of time.
  • @Position - runs the motor at the specified output until the specified amount of encoder ticks have occurred.
  • @Follower - the motor is configured to follow another Talon and therefor is not commanded, only measured.

This subsystem has some examples of Talons being tested in various ways.

public class ExampleSubsystem extends SubsystemBase {

    private final TalonSRXConfiguration talonSRXConfiguration = new TalonSRXConfiguration();

    // default duration healthcheck at default output percentages in forward and reverse direction
    @HealthCheck
    private final TalonSRX talonOne = new TalonFX(1);

    // run each of 3 output percentages for 4 seconds each
    @HealthCheck
    @Timed(percentOutput = {0.5, 0.75, -0.25}, duration = 4.0)
    private final TalonFX talonTwo = new TalonFX(2);

    // run each of 4 output percentages until 20,000 encoder ticks have occurred
    @HealthCheck
    @Position(percentOutput = {0.25, -0.25, 0.5, -0.5}, encoderChange = 20_000)
    private final TalonSRX talonThree = new TalonFX(3);

    // follows talonTwo (device id = 2) so just take measurements
    @HealthCheck
    @Follow(leader = 2)
    private final TalonFX talonFour = new Talon(4);

    public ExampleSubsystem() {
        talonFour.follow(talonTwo);
    }

    // These Health Check lifecycle methods are all optional.

    @BeforeHealthCheck
    private boolean beforeHealthCheck() {
        // perform any set-up such as positioning subsystems on the robot to
        // allow clear running, or override Talon configurations temporarily
        // while testing. Called periodically by the robot loop while running,
        // return true when finished.
        return true;
    }

    @AfterHealthCheck
    private boolean afterHealthCheck() {
        // perform any tear-down such as position subsystems, or resetting
        // Talon configurations. Called periodically by the robot loop while
        // running, return true when finished.
        return true;
    }

}

The @BeforeHealthCheck and @AfterHealthCheck methods are run before and after the health checks respectively and are called periodically by the robot loop while they are running. They should return true when finished. If there is more than one of either, you can specify the order in a similar fashion to @HealthCheck.

If you annotate an instance of SwerveDrive, it will run a series of standard health checks on the azimuth and drive Talons.

public class SwerveDriveSubsystem extends SubsystemBase {
    @HealthCheck
    private final SwerveDrive swerveDrive;
    // ...
}

To run the health checks, pass the subsystems to test to the HealthCheckCommand and connect to a suitable button.

public class RobotContainer {

    private final ExampleSubsystem exampleSubsystem = new ExampleSubsystem();
    private final SwerveDriveSubsystem swerveDriveSubsystem = new SwerveDriveSubsystem();

    public RobotContainer() {
        new Trigger(RobotController::getUserButton).onTrue(new HealthCheckCommand(exampleSubsystem, swerveDriveSubsystem));
        // ...
    }
}

After running the healthcheck, the JSON-formatted raw data is available at http://10.27.67.2:2767/data and can be saved and analyzed with a tool of choice. For example, the data can be loaded into a Pandas dataframe for analysis and visualization using the following.

import pandas as pd
import requests

r = requests.get("http://10.27.67.2:2767/data")
j = r.json()

meta = pd.DataFrame(j["meta"])
data = pd.DataFrame(j["data"])
df = pd.merge(meta, data, on="case", suffixes=('_set', '_measured'))
df.head(3)
case case_uuid name talon_set type output duration datetime msec_elapsed talon_measured voltage position speed supply_current stator_current
0 0 8efc0583-8f90-4ab8-9930-5403b1f51fb2 DriveSubsystem 0 time 0.25 5000000 2023-02-18 14:14:23.819275 0 0 0.0 0.0 0.0 0.125 0.0
1 0 8efc0583-8f90-4ab8-9930-5403b1f51fb2 DriveSubsystem 0 time 0.25 5000000 2023-02-18 14:14:23.819275 7144 0 0.0 0.0 0.0 0.125 0.0
2 0 8efc0583-8f90-4ab8-9930-5403b1f51fb2 DriveSubsystem 0 time 0.25 5000000 2023-02-18 14:14:23.819275 13316 0 0.0 0.0 0.0 0.125 0.0

thirdcoast's People

Contributors

jhh avatar kennyseybold avatar mwitcpalek avatar sidpagariya avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar

thirdcoast's Issues

RateLimit lastValue

@rkalnins - do we need to construct this object with this parameter? I'm assuming that the "first" lastValue is zero. Even if the joystick is held at max when enabling, the robot is not moving so the effective last value is zero.

Having said that, do we need to reset the lastValue back to zero when restarting the tele-op driving command?

Make ClientHandler an interface

Probably make sense at some point to refactor ClientHandler into a interface, it really only has two methods:

public interface ClientHandler {
  void start(Subscription sub);
  void shutdown;
}

Then we could implement a GrapherClientHandler and SplunkClientHandler with different payload formats.

At the same time I'd probably just put the client UDP destination port into the subscription since I'll be updating the format for ClientHandler.

Backing up a menu level when running something

Currently you just hit enter vs a new value to back out of controlling a talon or dio. Is there a reason we would not also add "B" as an option as well. I keep finding myself hitting "B" and then realizing I just need to hit enter. Nothing wrong with enter, just wondering is we should add B.

Combine tct Talon information display menu selections

The following menus are always used together so we want to merge them into one menu item:

  • List Selected Talons with Current Register Values
  • Inspect Selected Talons Configuration Settings

These actually display two very different sets of information so we will need to keep that clear in the merged information that is displayed.

A question about motion magic in your swerve control

l notice that this lib uses motion magic to control the turning motor. However , how do you calculate your paarameters like kP,kD , motioncurisevelocity , motionacceleration and so on? Would you provide any advice. l have read the CTRE's docs about motion magic, but l still don't know how to tune these parameters?

Any answer is appreciated!

Add Motion Magic Grapher Values

getMotionMagicAcceleration()
getMotionMagicActTrajPosition()
getMotionMagicActTrajVelocity()
getMotionMagicCruiseVelocity()

DIO input ouput crash

If you watch the DIOs as inputs, things work fine all the way through the grahper. But if you then use TCT to control a selected DIO as an output, TCT crashes
selecting digital output error

VM Period and Window not saved

The VM Period and Window are not saved when you save a configuration. They always load as the default 100ms and 64 samples. If you also de-select a talon and then re-select the same talon, they also reset to 100 and 64.

TCT added line feeds

It would help add clarity to the screen if we separated "events" with a line feed. Basically everything after the last line feed blank line goes together. I just find myself having to focus on where the relevant info is to the next keystoke I need to make. I might need to actually run this and show you live what I am talking about. Just wanted to capture the thought.

Determine StatusFrame default values

  • Upgrade a DS to 2018.
  • Run CTRE installer to intall Lifeboat.
  • Pull down the circle photo-bot.
  • Upgrade the roboRIO to 2018 image.
  • Run Lifeboat and upgrade roboRIO web pages.
  • Flash all the Talon firmware to 3.1.
  • Write a small robot program to call getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) on one of the Talons for each of the StatusFrameEnhanced values and record them.

Watching multiple types with the grapher

With the old BDC and Grapher you could select what type of device each channel of the grapher watched. For example you could watch the position of a talon controlled axis while also watching a DIO port waiting for something to get triggered. Not sure we can to that with TCT. In the old BDC, once you talked to something with BDC, it was on the list of available things the Grapher could watch. In TCT it appears only the active items in TCD are shown in the Grapher.

Digital inputs

We need the ability to read the digital inputs. TCT could just read all 10 ports and report them all at once. The grapher could show all 10 ports so that you could watch which ever combination you wanted.

TCT launch

This is minor ...

When you launch TCT, there is a small delay before you see anything happen. Is there a way to do some dot across the screen or some type of activity so that the moment you hit enter, you know something is going on. Just thinking about user comfort.

Reported Peak FWD and REV output voltages

Inspect Selected Talons always reports Peak FWD and REV output voltages to be "default" even when they are set and then verified in the Web interface to be set in the talon.

V17.0.22 problems

Something got missed here.

  1. While the analog raw shows up in TCT, it does not show up in the Grapher. And I did see it work at midlink with my own eyes.
  2. The order of the frame rate settings is not changed. General is not first.
  3. The servos and the DIO output stuff does work.
  4. I downloaded and confirmed V22 made it all the way to the Roborio twice.

List Selected Talons edit

VM Window and VM Period need to by exchanged in the screen order. The readout is correct, VM Period just needs to be before VM Window in the list.

Saving a current configuration

We need a way to see the current list of saved configurations to facilitate saving the configuration under a current name.

Talon Coast vs Brake mode

There does not appear to be a place to set Coast vs Brake mode. I would add this to section 3, Output Limits and Ramp rates.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.