mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[xrp] Add Reflectance sensor and rangefinder classes (#5673)
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
This commit is contained in:
@@ -0,0 +1,31 @@
|
||||
// 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.xrp;
|
||||
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.AnalogInput;
|
||||
|
||||
/** This class represents the ultrasonic rangefinder on an XRP robot. */
|
||||
public class XRPRangefinder {
|
||||
private final AnalogInput m_rangefinder = new AnalogInput(2);
|
||||
|
||||
/**
|
||||
* Get the measured distance in meters. Distance further than 4m will be reported as 4m.
|
||||
*
|
||||
* @return distance in meters
|
||||
*/
|
||||
public double getDistanceMeters() {
|
||||
return (m_rangefinder.getVoltage() / 5.0) * 4.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the measured distance in inches.
|
||||
*
|
||||
* @return distance in inches
|
||||
*/
|
||||
public double getDistanceInches() {
|
||||
return Units.metersToInches(getDistanceMeters());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,31 @@
|
||||
// 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.xrp;
|
||||
|
||||
import edu.wpi.first.wpilibj.AnalogInput;
|
||||
|
||||
/** This class represents the reflectance sensor pair on an XRP robot. */
|
||||
public class XRPReflectanceSensor {
|
||||
private final AnalogInput m_leftSensor = new AnalogInput(0);
|
||||
private final AnalogInput m_rightSensor = new AnalogInput(1);
|
||||
|
||||
/**
|
||||
* Returns the reflectance value of the left sensor.
|
||||
*
|
||||
* @return value between 0.0 (white) and 1.0 (black).
|
||||
*/
|
||||
public double getLeftReflectanceValue() {
|
||||
return m_leftSensor.getVoltage() / 5.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the reflectance value of the right sensor.
|
||||
*
|
||||
* @return value between 0.0 (white) and 1.0 (black).
|
||||
*/
|
||||
public double getRightReflectanceValue() {
|
||||
return m_rightSensor.getVoltage() / 5.0;
|
||||
}
|
||||
}
|
||||
11
xrpVendordep/src/main/native/cpp/xrp/XRPRangefinder.cpp
Normal file
11
xrpVendordep/src/main/native/cpp/xrp/XRPRangefinder.cpp
Normal file
@@ -0,0 +1,11 @@
|
||||
// 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 "frc/xrp/XRPRangefinder.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
units::meter_t XRPRangefinder::GetDistance() const {
|
||||
return units::meter_t{m_rangefinder.GetVoltage() / 5.0 * 4.0};
|
||||
}
|
||||
@@ -0,0 +1,15 @@
|
||||
// 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 "frc/xrp/XRPReflectanceSensor.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
double XRPReflectanceSensor::GetLeftReflectanceValue() const {
|
||||
return m_leftSensor.GetVoltage() / 5.0;
|
||||
}
|
||||
|
||||
double XRPReflectanceSensor::GetRightReflectanceValue() const {
|
||||
return m_rightSensor.GetVoltage() / 5.0;
|
||||
}
|
||||
@@ -0,0 +1,29 @@
|
||||
// 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.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogInput.h>
|
||||
|
||||
#include <units/length.h>
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* This class represents the reflectance sensor pair
|
||||
* on the XRP robot.
|
||||
*/
|
||||
class XRPRangefinder {
|
||||
public:
|
||||
/**
|
||||
* Return the measured distance in meters. Distances further than 4 meters
|
||||
* will be reported as 4 meters.
|
||||
*/
|
||||
units::meter_t GetDistance() const;
|
||||
|
||||
private:
|
||||
frc::AnalogInput m_rangefinder{2};
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -0,0 +1,34 @@
|
||||
// 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.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogInput.h>
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* This class represents the reflectance sensor pair
|
||||
* on the XRP robot.
|
||||
*/
|
||||
class XRPReflectanceSensor {
|
||||
public:
|
||||
/**
|
||||
* Return the reflectance value of the left sensor.
|
||||
* Value ranges from 0.0 (white) to 1.0 (black)
|
||||
*/
|
||||
double GetLeftReflectanceValue() const;
|
||||
|
||||
/**
|
||||
* Return the reflectance value of the right sensor.
|
||||
* Value ranges from 0.0 (white) to 1.0 (black)
|
||||
*/
|
||||
double GetRightReflectanceValue() const;
|
||||
|
||||
private:
|
||||
frc::AnalogInput m_leftSensor{0};
|
||||
frc::AnalogInput m_rightSensor{1};
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
Reference in New Issue
Block a user