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 org.wpilib.math.kinematics; 006 007import org.wpilib.math.geometry.Twist2d; 008import org.wpilib.math.interpolation.Interpolator; 009 010/** 011 * Helper class that converts a chassis velocity (dx and dtheta components) into wheel velocities 012 * and chassis accelerations into wheel accelerations. Robot code should not use this directly- 013 * Instead, use the particular type for your drivetrain (e.g., {@link DifferentialDriveKinematics}). 014 * 015 * @param <P> The type of the wheel positions. 016 * @param <S> The type of the wheel velocities. 017 * @param <A> The type of the wheel accelerations. 018 */ 019public interface Kinematics<P, S, A> extends Interpolator<P> { 020 /** 021 * Performs forward kinematics to return the resulting chassis velocity from the wheel velocities. 022 * This method is often used for odometry -- determining the robot's position on the field using 023 * data from the real-world velocity of each wheel on the robot. 024 * 025 * @param wheelVelocities The velocities of the wheels. 026 * @return The chassis velocity. 027 */ 028 ChassisVelocities toChassisVelocities(S wheelVelocities); 029 030 /** 031 * Performs inverse kinematics to return the wheel velocities from a desired chassis velocity. 032 * This method is often used to convert joystick values into wheel velocities. 033 * 034 * @param chassisVelocities The desired chassis velocity. 035 * @return The wheel velocities. 036 */ 037 S toWheelVelocities(ChassisVelocities chassisVelocities); 038 039 /** 040 * Performs forward kinematics to return the resulting chassis accelerations from the wheel 041 * accelerations. This method is often used for dynamics calculations -- determining the robot's 042 * acceleration on the field using data from the real-world acceleration of each wheel on the 043 * robot. 044 * 045 * @param wheelAccelerations The accelerations of the wheels. 046 * @return The chassis accelerations. 047 */ 048 ChassisAccelerations toChassisAccelerations(A wheelAccelerations); 049 050 /** 051 * Performs inverse kinematics to return the wheel accelerations from a desired chassis 052 * acceleration. This method is often used for dynamics calculations -- converting desired robot 053 * accelerations into individual wheel accelerations. 054 * 055 * @param chassisAccelerations The desired chassis accelerations. 056 * @return The wheel accelerations. 057 */ 058 A toWheelAccelerations(ChassisAccelerations chassisAccelerations); 059 060 /** 061 * Performs forward kinematics to return the resulting Twist2d from the given change in wheel 062 * positions. This method is often used for odometry -- determining the robot's position on the 063 * field using changes in the distance driven by each wheel on the robot. 064 * 065 * @param start The starting distances driven by the wheels. 066 * @param end The ending distances driven by the wheels. 067 * @return The resulting Twist2d in the robot's movement. 068 */ 069 Twist2d toTwist2d(P start, P end); 070 071 /** 072 * Returns a copy of the wheel positions object. 073 * 074 * @param positions The wheel positions object to copy. 075 * @return A copy. 076 */ 077 P copy(P positions); 078 079 /** 080 * Copies the value of the wheel positions object into the output. 081 * 082 * @param positions The wheel positions object to copy. Will not be modified. 083 * @param output The output variable of the copy operation. Will have the same value as the 084 * positions object after the call. 085 */ 086 void copyInto(P positions, P output); 087}