WPILibC++ 2024.3.2
MecanumDriveOdometry.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <wpi/SymbolExports.h>
8#include <wpi/timestamp.h>
9
10#include "frc/geometry/Pose2d.h"
15#include "units/time.h"
16
17namespace frc {
18
19/**
20 * Class for mecanum drive odometry. Odometry allows you to track the robot's
21 * position on the field over a course of a match using readings from your
22 * mecanum wheel encoders.
23 *
24 * Teams can use odometry during the autonomous period for complex tasks like
25 * path following. Furthermore, odometry can be used for latency compensation
26 * when using computer-vision systems.
27 */
29 : public Odometry<MecanumDriveWheelSpeeds, MecanumDriveWheelPositions> {
30 public:
31 /**
32 * Constructs a MecanumDriveOdometry object.
33 *
34 * @param kinematics The mecanum drive kinematics for your drivetrain.
35 * @param gyroAngle The angle reported by the gyroscope.
36 * @param wheelPositions The current distances measured by each wheel.
37 * @param initialPose The starting position of the robot on the field.
38 */
40 MecanumDriveKinematics kinematics, const Rotation2d& gyroAngle,
41 const MecanumDriveWheelPositions& wheelPositions,
42 const Pose2d& initialPose = Pose2d{});
43
44 private:
45 MecanumDriveKinematics m_kinematicsImpl;
46};
47
48} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:44
Class for mecanum drive odometry.
Definition: MecanumDriveOdometry.h:29
MecanumDriveOdometry(MecanumDriveKinematics kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Constructs a MecanumDriveOdometry object.
Class for odometry.
Definition: Odometry.h:28
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Definition: AprilTagPoseEstimator.h:15
Represents the wheel positions for a mecanum drive drivetrain.
Definition: MecanumDriveWheelPositions.h:16