001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) FIRST 2008-2017. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj; 009 010import edu.wpi.first.wpilibj.hal.AnalogGyroJNI; 011import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType; 012import edu.wpi.first.wpilibj.hal.HAL; 013import edu.wpi.first.wpilibj.interfaces.Gyro; 014import edu.wpi.first.wpilibj.livewindow.LiveWindow; 015import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; 016 017/** 018 * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class 019 * tracks the robots heading based on the starting position. As the robot rotates the new heading is 020 * computed by integrating the rate of rotation returned by the sensor. When the class is 021 * instantiated, it does a short calibration routine where it samples the gyro while at rest to 022 * determine the default offset. This is subtracted from each sample to determine the heading. 023 * 024 * <p>This class is for gyro sensors that connect to an analog input. 025 */ 026public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowSendable { 027 028 private static final double kDefaultVoltsPerDegreePerSecond = 0.007; 029 protected AnalogInput m_analog; 030 private boolean m_channelAllocated = false; 031 032 private int m_gyroHandle = 0; 033 034 /** 035 * Initialize the gyro. Calibration is handled by calibrate(). 036 */ 037 public void initGyro() { 038 039 if (m_gyroHandle == 0) { 040 m_gyroHandle = AnalogGyroJNI.initializeAnalogGyro(m_analog.m_port); 041 } 042 043 AnalogGyroJNI.setupAnalogGyro(m_gyroHandle); 044 045 HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel()); 046 LiveWindow.addSensor("AnalogGyro", m_analog.getChannel(), this); 047 } 048 049 @Override 050 public void calibrate() { 051 AnalogGyroJNI.calibrateAnalogGyro(m_gyroHandle); 052 } 053 054 /** 055 * Gyro constructor using the channel number 056 * 057 * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board 058 * channels 0-1. 059 */ 060 public AnalogGyro(int channel) { 061 this(new AnalogInput(channel)); 062 m_channelAllocated = true; 063 } 064 065 /** 066 * Gyro constructor with a precreated analog channel object. Use this constructor when the analog 067 * channel needs to be shared. 068 * 069 * @param channel The AnalogInput object that the gyro is connected to. Gyros can only be used on 070 * on-board channels 0-1. 071 */ 072 public AnalogGyro(AnalogInput channel) { 073 m_analog = channel; 074 if (m_analog == null) { 075 throw new NullPointerException("AnalogInput supplied to Gyro constructor is null"); 076 } 077 initGyro(); 078 calibrate(); 079 } 080 081 /** 082 * Gyro constructor using the channel number along with parameters for presetting the center and 083 * offset values. Bypasses calibration. 084 * 085 * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board 086 * channels 0-1. 087 * @param center Preset uncalibrated value to use as the accumulator center value. 088 * @param offset Preset uncalibrated value to use as the gyro offset. 089 */ 090 public AnalogGyro(int channel, int center, double offset) { 091 this(new AnalogInput(channel), center, offset); 092 m_channelAllocated = true; 093 } 094 095 /** 096 * Gyro constructor with a precreated analog channel object along with parameters for presetting 097 * the center and offset values. Bypasses calibration. 098 * 099 * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board 100 * channels 0-1. 101 * @param center Preset uncalibrated value to use as the accumulator center value. 102 * @param offset Preset uncalibrated value to use as the gyro offset. 103 */ 104 public AnalogGyro(AnalogInput channel, int center, double offset) { 105 m_analog = channel; 106 if (m_analog == null) { 107 throw new NullPointerException("AnalogInput supplied to Gyro constructor is null"); 108 } 109 initGyro(); 110 AnalogGyroJNI.setAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond, 111 offset, center); 112 reset(); 113 } 114 115 @Override 116 public void reset() { 117 AnalogGyroJNI.resetAnalogGyro(m_gyroHandle); 118 } 119 120 /** 121 * Delete (free) the accumulator and the analog components used for the gyro. 122 */ 123 @Override 124 public void free() { 125 if (m_analog != null && m_channelAllocated) { 126 m_analog.free(); 127 } 128 m_analog = null; 129 AnalogGyroJNI.freeAnalogGyro(m_gyroHandle); 130 } 131 132 @Override 133 public double getAngle() { 134 if (m_analog == null) { 135 return 0.0; 136 } else { 137 return AnalogGyroJNI.getAnalogGyroAngle(m_gyroHandle); 138 } 139 } 140 141 @Override 142 public double getRate() { 143 if (m_analog == null) { 144 return 0.0; 145 } else { 146 return AnalogGyroJNI.getAnalogGyroRate(m_gyroHandle); 147 } 148 } 149 150 /** 151 * Return the gyro offset value set during calibration to use as a future preset. 152 * 153 * @return the current offset value 154 */ 155 public double getOffset() { 156 return AnalogGyroJNI.getAnalogGyroOffset(m_gyroHandle); 157 } 158 159 /** 160 * Return the gyro center value set during calibration to use as a future preset. 161 * 162 * @return the current center value 163 */ 164 public int getCenter() { 165 return AnalogGyroJNI.getAnalogGyroCenter(m_gyroHandle); 166 } 167 168 /** 169 * Set the gyro sensitivity. This takes the number of volts/degree/second sensitivity of the gyro 170 * and uses it in subsequent calculations to allow the code to work with multiple gyros. This 171 * value is typically found in the gyro datasheet. 172 * 173 * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second. 174 */ 175 public void setSensitivity(double voltsPerDegreePerSecond) { 176 AnalogGyroJNI.setAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle, 177 voltsPerDegreePerSecond); 178 } 179 180 /** 181 * Set the size of the neutral zone. Any voltage from the gyro less than this amount from the 182 * center is considered stationary. Setting a deadband will decrease the amount of drift when the 183 * gyro isn't rotating, but will make it less accurate. 184 * 185 * @param volts The size of the deadband in volts 186 */ 187 void setDeadband(double volts) { 188 AnalogGyroJNI.setAnalogGyroDeadband(m_gyroHandle, volts); 189 } 190}