WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
MecanumDriveOdometry3d.hpp
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
13
14namespace wpi::math {
15
16/**
17 * Class for mecanum drive odometry. Odometry allows you to track the robot's
18 * position on the field over a course of a match using readings from your
19 * mecanum wheel encoders.
20 *
21 * Teams can use odometry during the autonomous period for complex tasks like
22 * path following. Furthermore, odometry can be used for latency compensation
23 * when using computer-vision systems.
24 */
26 : public Odometry3d<MecanumDriveWheelPositions, MecanumDriveWheelVelocities,
27 MecanumDriveWheelAccelerations> {
28 public:
29 /**
30 * Constructs a MecanumDriveOdometry3d object.
31 *
32 * @param kinematics The mecanum drive kinematics for your drivetrain.
33 * @param gyroAngle The angle reported by the gyroscope.
34 * @param wheelPositions The current distances measured by each wheel.
35 * @param initialPose The starting position of the robot on the field.
36 */
38 MecanumDriveKinematics kinematics, const Rotation3d& gyroAngle,
39 const MecanumDriveWheelPositions& wheelPositions,
40 const Pose3d& initialPose = Pose3d{});
41
42 private:
43 MecanumDriveKinematics m_kinematicsImpl;
44};
45
46} // namespace wpi::math
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel v...
Definition MecanumDriveKinematics.hpp:48
MecanumDriveOdometry3d(MecanumDriveKinematics kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
Constructs a MecanumDriveOdometry3d object.
Odometry3d(const Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations > &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
Definition Odometry3d.hpp:41
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:28
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
Definition LinearSystem.hpp:20
Represents the wheel positions for a mecanum drive drivetrain.
Definition MecanumDriveWheelPositions.hpp:15