2024-05-24 15:55:30 -04:00
|
|
|
// 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.simulation;
|
|
|
|
|
|
|
|
|
|
import edu.wpi.first.hal.SimDouble;
|
|
|
|
|
import edu.wpi.first.wpilibj.SharpIR;
|
|
|
|
|
|
2024-05-24 14:02:22 -07:00
|
|
|
/** Simulation class for Sharp IR sensors. */
|
2024-05-24 15:55:30 -04:00
|
|
|
public class SharpIRSim {
|
|
|
|
|
private final SimDouble m_simRange;
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Constructor.
|
|
|
|
|
*
|
|
|
|
|
* @param sharpIR The real sensor to simulate
|
|
|
|
|
*/
|
|
|
|
|
public SharpIRSim(SharpIR sharpIR) {
|
|
|
|
|
this(sharpIR.getChannel());
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Constructor.
|
|
|
|
|
*
|
|
|
|
|
* @param channel Analog channel for this sensor
|
|
|
|
|
*/
|
|
|
|
|
public SharpIRSim(int channel) {
|
|
|
|
|
SimDeviceSim simDevice = new SimDeviceSim("SharpIR", channel);
|
2025-02-10 07:23:04 -08:00
|
|
|
m_simRange = simDevice.getDouble("Range (m)");
|
2024-05-24 15:55:30 -04:00
|
|
|
}
|
|
|
|
|
|
2024-05-24 14:02:22 -07:00
|
|
|
/**
|
2025-02-10 07:23:04 -08:00
|
|
|
* Set the range in meters returned by the distance sensor.
|
2024-05-24 14:02:22 -07:00
|
|
|
*
|
2025-02-10 07:23:04 -08:00
|
|
|
* @param range range in meters of the target returned by the sensor
|
2024-05-24 14:02:22 -07:00
|
|
|
*/
|
2025-02-10 07:23:04 -08:00
|
|
|
public void setRange(double range) {
|
|
|
|
|
m_simRange.set(range);
|
2024-05-24 15:55:30 -04:00
|
|
|
}
|
|
|
|
|
}
|