Files
allwpilib/wpilibc/shared/include/interfaces/Gyro.h
Fredric Silberberg 6d854afb0e WPILib Reorganization
This is a major restructuring of the WPILib repository to simply build
procedures and remove the remnants of Maven from everything except the
eclipse plugins. Gradle files have been largely simplified or rewritten,
taking advantage of splitting up parts of the build into separate build
files for ease of reading.

The eclipse plugins are now in a separate project, as is ntcore. All
dependencies are resolved via Maven dependencies, with the
Jenkins-maintained WPILib repo. Project structures have also been
simplified: we no longer have separate subprojects inside wpilibc and
wpilibj. Where possible, these changes hav been done with git renames,
to make sure we still have full history for all repositories. Other
unrelated subprojects have also been broken out: OutlineViewer is now a
separate project.

Change-Id: Ib4e2a6e1a2f66427a14f16612b0e0d69ed661878
2015-11-21 18:26:49 -05:00

55 lines
2.1 KiB
C++

/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2014. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
/*----------------------------------------------------------------------------*/
#pragma once
/**
* Interface for yaw rate gyros
*/
class Gyro {
public:
virtual ~Gyro() = default;
/**
* Initialize the gyro. Calibrate the gyro by running for a number of samples
* and computing the center value. Then use the center value as the
* Accumulator center value for subsequent measurements. It's important to
* make sure that the robot is not moving while the centering calculations are
* in progress, this is typically done when the robot is first turned on while
* it's sitting at rest before the competition starts.
*/
virtual void InitGyro() = 0;
/**
* Reset the gyro. Resets the gyro to a heading of zero. This can be used if
* there is significant drift in the gyro and it needs to be recalibrated
* after it has been running.
*/
virtual void Reset() = 0;
/**
* Return the actual angle in degrees that the robot is currently facing.
*
* The angle is based on the current accumulator value corrected by the
* oversampling rate, the gyro type and the A/D calibration values. The angle
* is continuous, that is it will continue from 360 to 361 degrees. This
* allows algorithms that wouldn't want to see a discontinuity in the gyro
* output as it sweeps past from 360 to 0 on the second time around.
*
* @return the current heading of the robot in degrees. This heading is based
* on integration of the returned rate from the gyro.
*/
virtual float GetAngle() const = 0;
/**
* Return the rate of rotation of the gyro
*
* The rate is based on the most recent reading of the gyro analog value
*
* @return the current rate in degrees per second
*/
virtual double GetRate() const = 0;
};