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.FRCNetComm.tResourceType; 011import edu.wpi.first.wpilibj.hal.HAL; 012import edu.wpi.first.wpilibj.livewindow.LiveWindow; 013import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; 014import edu.wpi.first.wpilibj.tables.ITable; 015 016 017/** 018 * Handle operation of an analog accelerometer. The accelerometer reads acceleration directly 019 * through the sensor. Many sensors have multiple axis and can be treated as multiple devices. Each 020 * is calibrated by finding the center value over a period of time. 021 */ 022public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWindowSendable { 023 024 private AnalogInput m_analogChannel; 025 private double m_voltsPerG = 1.0; 026 private double m_zeroGVoltage = 2.5; 027 private boolean m_allocatedChannel; 028 protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; 029 030 /** 031 * Common initialization. 032 */ 033 private void initAccelerometer() { 034 HAL.report(tResourceType.kResourceType_Accelerometer, 035 m_analogChannel.getChannel()); 036 LiveWindow.addSensor("Accelerometer", m_analogChannel.getChannel(), this); 037 } 038 039 /** 040 * Create a new instance of an accelerometer. 041 * 042 * <p>The constructor allocates desired analog channel. 043 * 044 * @param channel The channel number for the analog input the accelerometer is connected to 045 */ 046 public AnalogAccelerometer(final int channel) { 047 m_allocatedChannel = true; 048 m_analogChannel = new AnalogInput(channel); 049 initAccelerometer(); 050 } 051 052 /** 053 * Create a new instance of Accelerometer from an existing AnalogChannel. Make a new instance of 054 * accelerometer given an AnalogChannel. This is particularly useful if the port is going to be 055 * read as an analog channel as well as through the Accelerometer class. 056 * 057 * @param channel The existing AnalogInput object for the analog input the accelerometer is 058 * connected to 059 */ 060 public AnalogAccelerometer(AnalogInput channel) { 061 m_allocatedChannel = false; 062 if (channel == null) { 063 throw new NullPointerException("Analog Channel given was null"); 064 } 065 m_analogChannel = channel; 066 initAccelerometer(); 067 } 068 069 /** 070 * Delete the analog components used for the accelerometer. 071 */ 072 @Override 073 public void free() { 074 if (m_analogChannel != null && m_allocatedChannel) { 075 m_analogChannel.free(); 076 } 077 m_analogChannel = null; 078 } 079 080 /** 081 * Return the acceleration in Gs. 082 * 083 * <p>The acceleration is returned units of Gs. 084 * 085 * @return The current acceleration of the sensor in Gs. 086 */ 087 public double getAcceleration() { 088 return (m_analogChannel.getAverageVoltage() - m_zeroGVoltage) / m_voltsPerG; 089 } 090 091 /** 092 * Set the accelerometer sensitivity. 093 * 094 * <p>This sets the sensitivity of the accelerometer used for calculating the acceleration. The 095 * sensitivity varies by accelerometer model. There are constants defined for various models. 096 * 097 * @param sensitivity The sensitivity of accelerometer in Volts per G. 098 */ 099 public void setSensitivity(double sensitivity) { 100 m_voltsPerG = sensitivity; 101 } 102 103 /** 104 * Set the voltage that corresponds to 0 G. 105 * 106 * <p>The zero G voltage varies by accelerometer model. There are constants defined for various 107 * models. 108 * 109 * @param zero The zero G voltage. 110 */ 111 public void setZero(double zero) { 112 m_zeroGVoltage = zero; 113 } 114 115 @Override 116 public void setPIDSourceType(PIDSourceType pidSource) { 117 m_pidSource = pidSource; 118 } 119 120 @Override 121 public PIDSourceType getPIDSourceType() { 122 return m_pidSource; 123 } 124 125 /** 126 * Get the Acceleration for the PID Source parent. 127 * 128 * @return The current acceleration in Gs. 129 */ 130 @Override 131 public double pidGet() { 132 return getAcceleration(); 133 } 134 135 @Override 136 public String getSmartDashboardType() { 137 return "Accelerometer"; 138 } 139 140 /* 141 * Live Window code, only does anything if live window is activated. 142 */ 143 private ITable m_table; 144 145 @Override 146 public void initTable(ITable subtable) { 147 m_table = subtable; 148 updateTable(); 149 } 150 151 @Override 152 public ITable getTable() { 153 return m_table; 154 } 155 156 @Override 157 public void updateTable() { 158 if (m_table != null) { 159 m_table.putNumber("Value", getAcceleration()); 160 } 161 } 162 163 /** 164 * Analog Channels don't have to do anything special when entering the LiveWindow. {@inheritDoc} 165 */ 166 @Override 167 public void startLiveWindowMode() { 168 } 169 170 /** 171 * Analog Channels don't have to do anything special when exiting the LiveWindow. {@inheritDoc} 172 */ 173 @Override 174 public void stopLiveWindowMode() { 175 } 176}