diff --git a/source/docs/software/advanced-controls/geometry/coordinate-systems.rst b/source/docs/software/advanced-controls/geometry/coordinate-systems.rst deleted file mode 100644 index f5a83d8221..0000000000 --- a/source/docs/software/advanced-controls/geometry/coordinate-systems.rst +++ /dev/null @@ -1,31 +0,0 @@ -.. include:: - -Coordinate Systems -================== - -In FRC\ |reg|, there are two main coordinate systems that we use for representing objects' positions. - -Field Coordinate System ------------------------ - -The field coordinate system (or global coordinate system) is an absolute coordinate system where a point on the field is designated as the origin. Positive :math:`\theta` (theta) is in the counter-clockwise direction, and the positive x-axis points away from your alliance's driver station wall, and the positive y-axis is perpendicular and to the left of the positive x-axis. - -.. image:: diagrams/field-system.svg - :alt: In this system the coordinates are fixed based upon the field. - -.. note:: The axes are shown at the middle of the field for visibility. The origins of the coordinate system for each alliance are shown below. - -Below is an example of a field coordinate system overlaid on the 2020 FRC field. The red axes shown are for the red alliance, and the blue axes shown are for the blue alliance. - -.. image:: images/infinite-recharge.jpg - :alt: Image of the Infinite Recharge field. - -Robot Coordinate System ------------------------ - -The robot coordinate system (or local coordinate system) is a relative coordinate system where the robot is the origin. The direction the robot is facing is the positive x axis, and the positive y axis is perpendicular, to the left of the robot. Positive :math:`\theta` is counter-clockwise. - -.. note:: WPILib's ``Gyro`` class is clockwise-positive, so you have to invert the reading in order to get the rotation with either coordinate system. - -.. image:: diagrams/robot-system.svg - :alt: The robot coordinate system is based on the robot's position. diff --git a/source/docs/software/advanced-controls/geometry/diagrams/field-system.svg b/source/docs/software/advanced-controls/geometry/diagrams/field-system.svg deleted file mode 100644 index 76b19cf9e6..0000000000 --- a/source/docs/software/advanced-controls/geometry/diagrams/field-system.svg +++ /dev/null @@ -1,3 +0,0 @@ - - -
+θ
x
x
y
y
Viewer does not support full SVG 1.1
\ No newline at end of file diff --git a/source/docs/software/advanced-controls/geometry/diagrams/robot-system.svg b/source/docs/software/advanced-controls/geometry/diagrams/robot-system.svg deleted file mode 100644 index be85b55b93..0000000000 --- a/source/docs/software/advanced-controls/geometry/diagrams/robot-system.svg +++ /dev/null @@ -1,3 +0,0 @@ - - -
+θ
x
x
y
y
Viewer does not support full SVG 1.1
\ No newline at end of file diff --git a/source/docs/software/advanced-controls/geometry/images/infinite-recharge.jpg b/source/docs/software/advanced-controls/geometry/images/infinite-recharge.jpg deleted file mode 100644 index 7e6b4f2ce3..0000000000 Binary files a/source/docs/software/advanced-controls/geometry/images/infinite-recharge.jpg and /dev/null differ diff --git a/source/docs/software/advanced-controls/geometry/index.rst b/source/docs/software/advanced-controls/geometry/index.rst index 90a79d7fc8..cfddeb1306 100644 --- a/source/docs/software/advanced-controls/geometry/index.rst +++ b/source/docs/software/advanced-controls/geometry/index.rst @@ -6,6 +6,5 @@ This section covers the geometry classes of WPILib. .. toctree:: :maxdepth: 1 - coordinate-systems pose transformations diff --git a/source/docs/software/basic-programming/coordinate-system.rst b/source/docs/software/basic-programming/coordinate-system.rst index f6c22b5bf1..492a56f21d 100644 --- a/source/docs/software/basic-programming/coordinate-system.rst +++ b/source/docs/software/basic-programming/coordinate-system.rst @@ -37,11 +37,13 @@ In most cases in WPILib programming, 0° is aligned with the positive X axis, an The figure above shows the unit circle with common angles labeled in degrees (°) and radians (rad). Notice that rotation to the right is negative, and the range for the whole unit circle is -180° to 180° (-Pi radians to Pi radians). +.. note:: The range is (-180, 180], meaning it is exclusive of -180° and inclusive of 180°. + There are some places you may choose to use a different range, such as 0° to 360° or 0 to 1 rotation, but be aware that many core WPILib classes and FRC tools are built with the unit circle above. -.. note:: The range is (-180, 180], meaning it is exclusive of -180° and inclusive of 180°. +.. warning:: Some gyros/IMUs use CW positive rotation, such as the NavX IMU. Care must be taken to handle rotation properly, sensor values may need to be inverted. Read the documentation and verify that rotation is CCW positive. -.. warning:: Some gyros/IMUs use CW positive rotation, such as the NavX IMU. Care must be taken to handle rotation properly, sensor values may need to be inverted. +.. warning:: Many sensors that read rotation around an axis, such as encoders and IMU's, read continuously. This means they read more than one rotation, so when rotating past 180° they read 181°, not -179°. Some sensors have configuration settings where you can choose their wrapping behavior and range, while others need to be handled in your code. Careful attention should be paid to make sure sensor readings are consistent and your control loop handles wrapping in the same way as your sensor. Joystick and controller coordinate system ---------------------------------------------- @@ -175,11 +177,32 @@ Like mecanum drivetrains, swerve drivetrains are holonomic and have the ability .. code-block:: python - // Drive using the X, Y, and Z axes of the joystick. + # Drive using the X, Y, and Z axes of the joystick. speeds = ChassisSpeeds(-self.stick.getY(), -self.stick.getX(), -self.stick.getZ()) The three arguments to the ``ChassisSpeeds`` constructor are the same as ``driveCartesian`` in the mecanum section above; ``xSpeed``, ``ySpeed``, and ``zRotation``. See the description of the arguments, and their joystick input in the section above. +Robot drive kinematics +---------------------- + +:doc:`Kinematics is a topic that is covered in a different section `, but it's worth discussing here in relation to the coordinate system. It is critically important that kinematics is configured using the coordinate system described above. Kinematics is a common starting point for coordinate system errors that then cascade to basic drivetrain control, field oriented driving, pose estimation, and path planning. + +When you construct a ``SwerveDriveKinematics`` or ``MecanumDriveKinematics`` object, you specify a translation from the center of your robot to each wheel. These translations use the coordinate system above, with the origin in the center of your robot. + +.. figure:: images/coordinate-system/kinematics.svg + :alt: Kinematics with translation signs + + Kinematics with translation signs + +For the robot in the diagram above, let's assume the distance between the front and rear wheels (wheelbase) is 2'. Let's also assume the distance between the left and right wheels (trackwidth) is also 2'. Our translations (x, y) would be like this: + +- Front left: (1', 1') +- Front right: (1', -1') +- Rear left: (-1', 1') +- Rear right: (-1', -1') + +.. warning:: A common error is to use an incorrect coordinate system where the positive Y axis points forward on the robot. The correct coordinate system has the positive X axis pointing forward. + Field coordinate systems ------------------------ @@ -300,3 +323,9 @@ Some things you need to consider when using this approach are: - There are cases where your alliance may change (or appear to change) after the code is initialized. When you are not connected to the FMS at a competition, you can change your alliance station in the Driver Station application at any time. Even when you are at a competition, your robot will usually initialize before connecting to the FMS so you will not have alliance information. If you are not using AprilTags, you may not have anything to adjust when the alliance changes. However, if you are using AprilTags and your robot has seen a tag and used it for pose estimation, you will need to adjust your origin and reset your estimated pose. - The field image in the ShuffleBoard Field2d widget follows the *Always blue origin* approach. If you want the widget to display the correct pose for your robot, you will need to change the origin for your estimated pose before sending it to the dashboard. + +Coordinate system programming tips and troubleshooting +------------------------------------------------------ + +In addition to the information and code examples above, here is a list of some common problem and their solutions. + diff --git a/source/docs/software/basic-programming/images/coordinate-system/kinematics.svg b/source/docs/software/basic-programming/images/coordinate-system/kinematics.svg new file mode 100644 index 0000000000..27cde6d23b --- /dev/null +++ b/source/docs/software/basic-programming/images/coordinate-system/kinematics.svg @@ -0,0 +1,166 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + Page-1 + + + Sheet.2 + + + + Sheet.3 + + + + Sheet.4 + +X + + + + +X + + Sheet.6 + -X + + + + -X + + Sheet.7 + +Y + + + + +Y + + Sheet.8 + -Y + + + + -Y + + Sheet.9 + (+, +) + + + + (+, +) + + Sheet.10 + (+, -) + + + + (+, -) + + Sheet.11 + (-, +) + + + + (-, +) + + Sheet.12 + (-, -) + + + + (-, -) + + Sheet.23 + + Sheet.15 + FRONT + + + + FRONT + + Square + + + + + + + Rectangle + + + + + + + Rectangle.17 + + + + + + + Rectangle.18 + + + + + + + Rectangle.19 + + + + + + + + diff --git a/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst index 272e4ddb47..e99b0191fe 100644 --- a/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst @@ -13,7 +13,7 @@ The ``DifferentialDriveOdometry`` class constructor requires three mandatory arg The optional argument is the starting pose of your robot on the field (as a ``Pose2d``). By default, the robot will start at ``x = 0, y = 0, theta = 0``. -.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. +.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :doc:`/docs/software/basic-programming/coordinate-system` for more information about the coordinate system. .. tab-set-code:: diff --git a/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst b/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst index 60383e91f8..2aa7ade885 100644 --- a/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst +++ b/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst @@ -1,6 +1,8 @@ Introduction to Kinematics and The ChassisSpeeds Class ====================================================== +.. note:: Kinematics and odometry uses a common coordinate system. You may wish to reference the :doc:`/docs/software/basic-programming/coordinate-system` section for details. + What is kinematics? ------------------- The kinematics suite contains classes for differential drive, swerve drive, and mecanum drive kinematics and odometry. The kinematics classes help convert between a universal ``ChassisSpeeds`` (`Java `__, `C++ `__, :external:py:class:`Python `)object, containing linear and angular velocities for a robot to usable speeds for each individual type of drivetrain i.e. left and right wheel speeds for a differential drive, four wheel speeds for a mecanum drive, or individual module states (speed and angle) for a swerve drive. diff --git a/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst b/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst index ca3f45b6ad..2ff0cb1c39 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst @@ -2,6 +2,8 @@ Mecanum Drive Kinematics ======================== The ``MecanumDriveKinematics`` class is a useful tool that converts between a ``ChassisSpeeds`` object and a ``MecanumDriveWheelSpeeds`` object, which contains velocities for each of the four wheels on a mecanum drive. +.. note:: Mecanum kinematics uses a common coordinate system. You may wish to reference the :doc:`/docs/software/basic-programming/coordinate-system` section for details. + Constructing the Kinematics Object ---------------------------------- The ``MecanumDriveKinematics`` class accepts four constructor arguments, with each argument being the location of a wheel relative to the robot center (as a ``Translation2d``). The order for the arguments is front left, front right, back left, and back right. The locations for the wheels must be relative to the center of the robot. Positive x values represent moving toward the front of the robot whereas positive y values represent moving toward the left of the robot. diff --git a/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst index 64c3643026..73baa1a68f 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst @@ -16,7 +16,7 @@ The mandatory arguments are: The fourth optional argument is the starting pose of your robot on the field (as a ``Pose2d``). By default, the robot will start at ``x = 0, y = 0, theta = 0``. -.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. +.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :doc:`/docs/software/basic-programming/coordinate-system` for more information about the coordinate system. .. tab-set-code:: diff --git a/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst b/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst index 337348f1c4..2d96b2de33 100644 --- a/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst @@ -2,6 +2,8 @@ Swerve Drive Kinematics ======================= The ``SwerveDriveKinematics`` class is a useful tool that converts between a ``ChassisSpeeds`` object and several ``SwerveModuleState`` objects, which contains velocities and angles for each swerve module of a swerve drive robot. +.. note:: Swerve drive kinematics uses a common coordinate system. You may wish to reference the :doc:`/docs/software/basic-programming/coordinate-system` section for details. + The swerve module state class ----------------------------- The ``SwerveModuleState`` class contains information about the velocity and angle of a singular module of a swerve drive. The constructor for a ``SwerveModuleState`` takes in two arguments, the velocity of the wheel on the module, and the angle of the module. diff --git a/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst index a6d8401345..35d357254d 100644 --- a/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst @@ -16,7 +16,7 @@ The mandatory arguments are: The fourth optional argument is the starting pose of your robot on the field (as a ``Pose2d``). By default, the robot will start at ``x = 0, y = 0, theta = 0``. -.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. +.. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :doc:`/docs/software/basic-programming/coordinate-system` for more information about the coordinate system. .. tab-set-code::