WPILibC++  unspecified
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Pages
AnalogGyro.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) FIRST 2008-2016. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in the root directory of */
5 /* the project. */
6 /*----------------------------------------------------------------------------*/
7 
8 #pragma once
9 
10 #include "GyroBase.h"
11 
12 class AnalogInput;
13 
32 class AnalogGyro : public GyroBase {
33  public:
34  static const uint32_t kOversampleBits = 10;
35  static const uint32_t kAverageBits = 0;
36  static constexpr float kSamplesPerSecond = 50.0;
37  static constexpr float kCalibrationSampleTime = 5.0;
38  static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007;
39 
40  explicit AnalogGyro(int32_t channel);
41  explicit AnalogGyro(AnalogInput *channel);
42  explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
43  AnalogGyro(int32_t channel, uint32_t center, float offset);
44  AnalogGyro(std::shared_ptr<AnalogInput> channel, uint32_t center, float offset);
45  virtual ~AnalogGyro() = default;
46 
47  float GetAngle() const override;
48  double GetRate() const override;
49  virtual uint32_t GetCenter() const;
50  virtual float GetOffset() const;
51  void SetSensitivity(float voltsPerDegreePerSecond);
52  void SetDeadband(float volts);
53  void Reset() override;
54  virtual void InitGyro();
55  void Calibrate() override;
56 
57  protected:
58  std::shared_ptr<AnalogInput> m_analog;
59 
60  private:
61  float m_voltsPerDegreePerSecond;
62  float m_offset;
63  uint32_t m_center;
64 };
void Calibrate() override
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.
Definition: AnalogGyro.cpp:141
virtual float GetOffset() const
Return the gyro offset value.
Definition: AnalogGyro.cpp:211
virtual uint32_t GetCenter() const
Return the gyro center value.
Definition: AnalogGyro.cpp:221
GyroBase is the common base class for Gyro implementations such as AnalogGyro.
Definition: GyroBase.h:21
void SetSensitivity(float voltsPerDegreePerSecond)
Set the gyro sensitivity.
Definition: AnalogGyro.cpp:235
Analog input class.
Definition: AnalogInput.h:32
void SetDeadband(float volts)
Set the size of the neutral zone.
Definition: AnalogGyro.cpp:247
float GetAngle() const override
Return the actual angle in degrees that the robot is currently facing.
Definition: AnalogGyro.cpp:174
double GetRate() const override
Return the rate of rotation of the gyro.
Definition: AnalogGyro.cpp:197
AnalogGyro(int32_t channel)
Gyro constructor using the Analog Input channel number.
Definition: AnalogGyro.cpp:26
Use a rate gyro to return the robots heading relative to a starting position.
Definition: AnalogGyro.h:32
void Reset() override
Reset the gyro.
Definition: AnalogGyro.cpp:104
virtual void InitGyro()
Initialize the gyro.
Definition: AnalogGyro.cpp:112