001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2008-2018 FIRST. 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.smartdashboard.SendableBuilder; 013 014import static java.util.Objects.requireNonNull; 015 016/** 017 * Handle operation of an analog accelerometer. The accelerometer reads acceleration directly 018 * through the sensor. Many sensors have multiple axis and can be treated as multiple devices. Each 019 * is calibrated by finding the center value over a period of time. 020 */ 021public class AnalogAccelerometer extends SensorBase implements PIDSource, Sendable { 022 private AnalogInput m_analogChannel; 023 private double m_voltsPerG = 1.0; 024 private double m_zeroGVoltage = 2.5; 025 private boolean m_allocatedChannel; 026 protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; 027 028 /** 029 * Common initialization. 030 */ 031 private void initAccelerometer() { 032 HAL.report(tResourceType.kResourceType_Accelerometer, 033 m_analogChannel.getChannel()); 034 setName("Accelerometer", m_analogChannel.getChannel()); 035 } 036 037 /** 038 * Create a new instance of an accelerometer. 039 * 040 * <p>The constructor allocates desired analog channel. 041 * 042 * @param channel The channel number for the analog input the accelerometer is connected to 043 */ 044 public AnalogAccelerometer(final int channel) { 045 this(new AnalogInput(channel)); 046 m_allocatedChannel = true; 047 addChild(m_analogChannel); 048 } 049 050 /** 051 * Create a new instance of Accelerometer from an existing AnalogChannel. Make a new instance of 052 * accelerometer given an AnalogChannel. This is particularly useful if the port is going to be 053 * read as an analog channel as well as through the Accelerometer class. 054 * 055 * @param channel The existing AnalogInput object for the analog input the accelerometer is 056 * connected to 057 */ 058 public AnalogAccelerometer(AnalogInput channel) { 059 requireNonNull(channel, "Analog Channel given was null"); 060 061 m_allocatedChannel = false; 062 m_analogChannel = channel; 063 initAccelerometer(); 064 } 065 066 /** 067 * Delete the analog components used for the accelerometer. 068 */ 069 @Override 070 public void free() { 071 super.free(); 072 if (m_analogChannel != null && m_allocatedChannel) { 073 m_analogChannel.free(); 074 } 075 m_analogChannel = null; 076 } 077 078 /** 079 * Return the acceleration in Gs. 080 * 081 * <p>The acceleration is returned units of Gs. 082 * 083 * @return The current acceleration of the sensor in Gs. 084 */ 085 public double getAcceleration() { 086 if (m_analogChannel == null) { 087 return 0.0; 088 } 089 return (m_analogChannel.getAverageVoltage() - m_zeroGVoltage) / m_voltsPerG; 090 } 091 092 /** 093 * Set the accelerometer sensitivity. 094 * 095 * <p>This sets the sensitivity of the accelerometer used for calculating the acceleration. The 096 * sensitivity varies by accelerometer model. There are constants defined for various models. 097 * 098 * @param sensitivity The sensitivity of accelerometer in Volts per G. 099 */ 100 public void setSensitivity(double sensitivity) { 101 m_voltsPerG = sensitivity; 102 } 103 104 /** 105 * Set the voltage that corresponds to 0 G. 106 * 107 * <p>The zero G voltage varies by accelerometer model. There are constants defined for various 108 * models. 109 * 110 * @param zero The zero G voltage. 111 */ 112 public void setZero(double zero) { 113 m_zeroGVoltage = zero; 114 } 115 116 @Override 117 public void setPIDSourceType(PIDSourceType pidSource) { 118 m_pidSource = pidSource; 119 } 120 121 @Override 122 public PIDSourceType getPIDSourceType() { 123 return m_pidSource; 124 } 125 126 /** 127 * Get the Acceleration for the PID Source parent. 128 * 129 * @return The current acceleration in Gs. 130 */ 131 @Override 132 public double pidGet() { 133 return getAcceleration(); 134 } 135 136 @Override 137 public void initSendable(SendableBuilder builder) { 138 builder.setSmartDashboardType("Accelerometer"); 139 builder.addDoubleProperty("Value", this::getAcceleration, null); 140 } 141}