mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib][sim] Add Onboard IMU Sim (#8855)
This provides the ability to simulate parts of the Onboard IMU at the HAL level. This allows team to use and simulate the IMU in code, and a follow up PR could be made to the halsim_gui to add a new widget to view and modify the data graphically. Since the C++ IMU uses radians for angles that is what I did for the simulator. Partially deals with #8845
This commit is contained in:
104
wpilibj/src/main/java/org/wpilib/simulation/OnboardIMUSim.java
Normal file
104
wpilibj/src/main/java/org/wpilib/simulation/OnboardIMUSim.java
Normal file
@@ -0,0 +1,104 @@
|
||||
// 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 org.wpilib.simulation;
|
||||
|
||||
import org.wpilib.hardware.hal.simulation.IMUDataJNI;
|
||||
|
||||
/** Class to control a simulated onboard IMU. */
|
||||
public final class OnboardIMUSim {
|
||||
private OnboardIMUSim() {
|
||||
throw new UnsupportedOperationException("This is a utility class!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the x-angle.
|
||||
*
|
||||
* @param angleRad the new angle
|
||||
*/
|
||||
public static void setAngleX(double angleRad) {
|
||||
IMUDataJNI.setAngleX(angleRad);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the y-angle.
|
||||
*
|
||||
* @param angleRad the new angle
|
||||
*/
|
||||
public static void setAngleY(double angleRad) {
|
||||
IMUDataJNI.setAngleY(angleRad);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the z-angle.
|
||||
*
|
||||
* @param angleRad the new angle
|
||||
*/
|
||||
public static void setAngleZ(double angleRad) {
|
||||
IMUDataJNI.setAngleZ(angleRad);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the x-gyro rate.
|
||||
*
|
||||
* @param rateRadPerSec the new rate
|
||||
*/
|
||||
public static void setGyroRateX(double rateRadPerSec) {
|
||||
IMUDataJNI.setGyroRateX(rateRadPerSec);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the y-gyro rate.
|
||||
*
|
||||
* @param rateRadPerSec the new rate
|
||||
*/
|
||||
public static void setGyroRateY(double rateRadPerSec) {
|
||||
IMUDataJNI.setGyroRateY(rateRadPerSec);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the z-gyro rate.
|
||||
*
|
||||
* @param rateRadPerSec the new rate
|
||||
*/
|
||||
public static void setGyroRateZ(double rateRadPerSec) {
|
||||
IMUDataJNI.setGyroRateZ(rateRadPerSec);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the x-accel rate.
|
||||
*
|
||||
* @param accelMpss the new acceleration
|
||||
*/
|
||||
public static void setAccelX(double accelMpss) {
|
||||
IMUDataJNI.setAccelX(accelMpss);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the y-accel rate.
|
||||
*
|
||||
* @param accelMpss the new acceleration
|
||||
*/
|
||||
public static void setAccelY(double accelMpss) {
|
||||
IMUDataJNI.setAccelY(accelMpss);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the z-accel rate.
|
||||
*
|
||||
* @param accelMpss the new acceleration
|
||||
*/
|
||||
public static void setAccelZ(double accelMpss) {
|
||||
IMUDataJNI.setAccelZ(accelMpss);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the yaw.
|
||||
*
|
||||
* @param angleRad the new yaw angle
|
||||
*/
|
||||
public static void setYaw(double angleRad) {
|
||||
IMUDataJNI.setYaw(angleRad);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,59 @@
|
||||
// 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 org.wpilib.hardware.imu;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.wpilib.simulation.OnboardIMUSim;
|
||||
|
||||
class OnboardIMUTest {
|
||||
@Test
|
||||
void testOnboardIMU() {
|
||||
OnboardIMU imu = new OnboardIMU(OnboardIMU.MountOrientation.FLAT);
|
||||
|
||||
assertEquals(0.0, imu.getAngleX());
|
||||
assertEquals(0.0, imu.getAngleY());
|
||||
assertEquals(0.0, imu.getAngleZ());
|
||||
|
||||
assertEquals(0.0, imu.getGyroRateX());
|
||||
assertEquals(0.0, imu.getGyroRateY());
|
||||
assertEquals(0.0, imu.getGyroRateZ());
|
||||
|
||||
assertEquals(0.0, imu.getAccelX());
|
||||
assertEquals(0.0, imu.getAccelY());
|
||||
assertEquals(0.0, imu.getAccelZ());
|
||||
|
||||
assertEquals(0.0, imu.getYawRadians());
|
||||
|
||||
OnboardIMUSim.setAngleX(1);
|
||||
OnboardIMUSim.setAngleY(2);
|
||||
OnboardIMUSim.setAngleZ(3);
|
||||
|
||||
OnboardIMUSim.setGyroRateX(3.504);
|
||||
OnboardIMUSim.setGyroRateY(1.91);
|
||||
OnboardIMUSim.setGyroRateZ(22.9);
|
||||
|
||||
OnboardIMUSim.setAccelX(-1);
|
||||
OnboardIMUSim.setAccelY(-2);
|
||||
OnboardIMUSim.setAccelZ(-3);
|
||||
|
||||
OnboardIMUSim.setYaw(1.234);
|
||||
|
||||
assertEquals(1.0, imu.getAngleX());
|
||||
assertEquals(2.0, imu.getAngleY());
|
||||
assertEquals(3.0, imu.getAngleZ());
|
||||
|
||||
assertEquals(3.504, imu.getGyroRateX());
|
||||
assertEquals(1.91, imu.getGyroRateY());
|
||||
assertEquals(22.9, imu.getGyroRateZ());
|
||||
|
||||
assertEquals(-1.0, imu.getAccelX());
|
||||
assertEquals(-2.0, imu.getAccelY());
|
||||
assertEquals(-3.0, imu.getAccelZ());
|
||||
|
||||
assertEquals(1.234, imu.getYawRadians());
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user