diff --git a/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp new file mode 100644 index 0000000000..89a157ece3 --- /dev/null +++ b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp @@ -0,0 +1,66 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include +#include +#include +#include +#include +#include +#include +#include + +/** + * ADXL346, 362 Accelerometer snippets for frc-docs. + * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html + */ +class Robot : public frc::TimedRobot { + public: + Robot() {} + + void TeleopPeriodic() override { + // Gets the current acceleration in the X axis + m_accelerometer345I2C.GetX(); + // Gets the current acceleration in the Y axis + m_accelerometer345I2C.GetY(); + // Gets the current acceleration in the Z axis + m_accelerometer345I2C.GetZ(); + + // Gets the current acceleration in the X axis + m_accelerometer345SPI.GetX(); + // Gets the current acceleration in the Y axis + m_accelerometer345SPI.GetY(); + // Gets the current acceleration in the Z axis + m_accelerometer345SPI.GetZ(); + + // Gets the current acceleration in the X axis + m_accelerometer362.GetX(); + // Gets the current acceleration in the Y axis + m_accelerometer362.GetY(); + // Gets the current acceleration in the Z axis + m_accelerometer362.GetZ(); + } + + private: + // Creates an ADXL345 accelerometer object on the MXP I2C port + // with a measurement range from -8 to 8 G's + frc::ADXL345_I2C m_accelerometer345I2C{frc::I2C::Port::kMXP, + frc::ADXL345_I2C::Range::kRange_8G}; + + // Creates an ADXL345 accelerometer object on the MXP SPI port + // with a measurement range from -8 to 8 G's + frc::ADXL345_SPI m_accelerometer345SPI{frc::SPI::Port::kMXP, + frc::ADXL345_SPI::Range::kRange_8G}; + + // Creates an ADXL362 accelerometer object on the MXP SPI port + // with a measurement range from -8 to 8 G's + frc::ADXL362 m_accelerometer362{frc::SPI::Port::kMXP, + frc::ADXL362::Range::kRange_8G}; +}; + +#ifndef RUNNING_FRC_TESTS +int main() { + return frc::StartRobot(); +} +#endif diff --git a/wpilibcExamples/src/main/cpp/snippets/snippets.json b/wpilibcExamples/src/main/cpp/snippets/snippets.json index 361e48b579..2577b0078c 100644 --- a/wpilibcExamples/src/main/cpp/snippets/snippets.json +++ b/wpilibcExamples/src/main/cpp/snippets/snippets.json @@ -114,5 +114,15 @@ ], "foldername": "AnalogAccelerometer", "gradlebase": "cpp" + }, + { + "name": "ADXLAccelerometers", + "description": "Snippets of ADXL 345 and 362 Accelerometers for frc-docs.", + "tags": [ + "Hardware", + "Accelerometer" + ], + "foldername": "ADXLAccelerometers", + "gradlebase": "cpp" } ] diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Main.java new file mode 100644 index 0000000000..ea62717693 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.snippets.adxlaccelerometers; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Robot.java new file mode 100644 index 0000000000..e206445f5e --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/adxlaccelerometers/Robot.java @@ -0,0 +1,57 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.snippets.adxlaccelerometers; + +import edu.wpi.first.wpilibj.ADXL345_I2C; +import edu.wpi.first.wpilibj.ADXL345_SPI; +import edu.wpi.first.wpilibj.ADXL362; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.SPI; +import edu.wpi.first.wpilibj.TimedRobot; + +/** + * ADXL345, 362 Accelerometer snippets for frc-docs. + * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html + */ +public class Robot extends TimedRobot { + // Creates an ADXL345 accelerometer object on the MXP I2C port + // with a measurement range from -8 to 8 G's + ADXL345_I2C m_accelerometer345I2C = new ADXL345_I2C(I2C.Port.kMXP, ADXL345_I2C.Range.k8G); + + // Creates an ADXL345 accelerometer object on the MXP SPI port + // with a measurement range from -8 to 8 G's + ADXL345_SPI m_accelerometer345SPI = new ADXL345_SPI(SPI.Port.kMXP, ADXL345_SPI.Range.k8G); + + // Creates an ADXL362 accelerometer object on the MXP SPI port + // with a measurement range from -8 to 8 G's + ADXL362 m_accelerometer362 = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G); + + /** Called once at the beginning of the robot program. */ + public Robot() {} + + @Override + public void teleopPeriodic() { + // Gets the current acceleration in the X axis + m_accelerometer345I2C.getX(); + // Gets the current acceleration in the Y axis + m_accelerometer345I2C.getY(); + // Gets the current acceleration in the Z axis + m_accelerometer345I2C.getZ(); + + // Gets the current acceleration in the X axis + m_accelerometer345SPI.getX(); + // Gets the current acceleration in the Y axis + m_accelerometer345SPI.getY(); + // Gets the current acceleration in the Z axis + m_accelerometer345SPI.getZ(); + + // Gets the current acceleration in the X axis + m_accelerometer362.getX(); + // Gets the current acceleration in the Y axis + m_accelerometer362.getY(); + // Gets the current acceleration in the Z axis + m_accelerometer362.getZ(); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json index beb69ab5e1..b8d8d3e38c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/snippets.json @@ -125,5 +125,16 @@ "foldername": "analogaccelerometer", "gradlebase": "java", "mainclass": "Main" + }, + { + "name": "ADXLAccelerometers", + "description": "Snippets of ADXL 345 and 362 accelerometers for frc-docs.", + "tags": [ + "Hardware", + "Accelerometer" + ], + "foldername": "adxlaccelerometers", + "gradlebase": "java", + "mainclass": "Main" } ]