001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.math.kinematics; 006 007import edu.wpi.first.math.geometry.Twist2d; 008import edu.wpi.first.math.interpolation.Interpolator; 009 010/** 011 * Helper class that converts a chassis velocity (dx and dtheta components) into wheel speeds. Robot 012 * code should not use this directly- Instead, use the particular type for your drivetrain (e.g., 013 * {@link DifferentialDriveKinematics}). 014 * 015 * @param <S> The type of the wheel speeds. 016 * @param <P> The type of the wheel positions. 017 */ 018public interface Kinematics<S, P> extends Interpolator<P> { 019 /** 020 * Performs forward kinematics to return the resulting chassis speed from the wheel speeds. This 021 * method is often used for odometry -- determining the robot's position on the field using data 022 * from the real-world speed of each wheel on the robot. 023 * 024 * @param wheelSpeeds The speeds of the wheels. 025 * @return The chassis speed. 026 */ 027 ChassisSpeeds toChassisSpeeds(S wheelSpeeds); 028 029 /** 030 * Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. This 031 * method is often used to convert joystick values into wheel speeds. 032 * 033 * @param chassisSpeeds The desired chassis speed. 034 * @return The wheel speeds. 035 */ 036 S toWheelSpeeds(ChassisSpeeds chassisSpeeds); 037 038 /** 039 * Performs forward kinematics to return the resulting Twist2d from the given change in wheel 040 * positions. This method is often used for odometry -- determining the robot's position on the 041 * field using changes in the distance driven by each wheel on the robot. 042 * 043 * @param start The starting distances driven by the wheels. 044 * @param end The ending distances driven by the wheels. 045 * @return The resulting Twist2d in the robot's movement. 046 */ 047 Twist2d toTwist2d(P start, P end); 048 049 /** 050 * Returns a copy of the wheel positions object. 051 * 052 * @param positions The wheel positions object to copy. 053 * @return A copy. 054 */ 055 P copy(P positions); 056 057 /** 058 * Copies the value of the wheel positions object into the output. 059 * 060 * @param positions The wheel positions object to copy. Will not be modified. 061 * @param output The output variable of the copy operation. Will have the same value as the 062 * positions object after the call. 063 */ 064 void copyInto(P positions, P output); 065}