mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
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
64 lines
2.2 KiB
C++
64 lines
2.2 KiB
C++
/*----------------------------------------------------------------------------*/
|
|
/* Copyright (c) FIRST 2008. 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
|
|
|
|
#include "GyroBase.h"
|
|
|
|
class AnalogInput;
|
|
|
|
/**
|
|
* Use a rate gyro to return the robots heading relative to a starting position.
|
|
* The Gyro class tracks the robots heading based on the starting position. As
|
|
* the robot
|
|
* rotates the new heading is computed by integrating the rate of rotation
|
|
* returned
|
|
* by the sensor. When the class is instantiated, it does a short calibration
|
|
* routine
|
|
* where it samples the gyro while at rest to determine the default offset. This
|
|
* is
|
|
* subtracted from each sample to determine the heading. This gyro class must be
|
|
* used
|
|
* with a channel that is assigned one of the Analog accumulators from the FPGA.
|
|
* See
|
|
* AnalogInput for the current accumulator assignments.
|
|
*
|
|
* This class is for gyro sensors that connect to an analog input.
|
|
*/
|
|
class AnalogGyro : public GyroBase {
|
|
public:
|
|
static const uint32_t kOversampleBits = 10;
|
|
static const uint32_t kAverageBits = 0;
|
|
static constexpr float kSamplesPerSecond = 50.0;
|
|
static constexpr float kCalibrationSampleTime = 5.0;
|
|
static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007;
|
|
|
|
explicit AnalogGyro(int32_t channel);
|
|
DEPRECATED(
|
|
"Raw pointers are deprecated; consider calling the AnalogGyro constructor"
|
|
" with a channel number or passing a shared_ptr instead.")
|
|
explicit AnalogGyro(AnalogInput *channel);
|
|
explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
|
|
virtual ~AnalogGyro() = default;
|
|
|
|
float GetAngle() const override;
|
|
double GetRate() const override;
|
|
void SetSensitivity(float voltsPerDegreePerSecond);
|
|
void SetDeadband(float volts);
|
|
void Reset() override;
|
|
void InitGyro() override;
|
|
|
|
std::string GetSmartDashboardType() const override;
|
|
|
|
protected:
|
|
std::shared_ptr<AnalogInput> m_analog;
|
|
|
|
private:
|
|
float m_voltsPerDegreePerSecond;
|
|
float m_offset;
|
|
uint32_t m_center;
|
|
};
|