Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[wpilib] Document simulation APIs #3079

Merged
merged 1 commit into from Jan 12, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
12 changes: 11 additions & 1 deletion hal/src/main/java/edu/wpi/first/hal/SimDevice.java
Expand Up @@ -4,7 +4,17 @@

package edu.wpi.first.hal;

/** A wrapper around a simulator device handle. */
/**
* A wrapper around a simulator device handle.
*
* <p>Teams: if you are using this class, you are likely confusing it for {@link
* edu.wpi.first.wpilibj.simulation.SimDeviceSim}.
*
* <p>Vendors: This class should be used from inside the device class to define the
* properties/fields of the device. Use {@link #create} to get a SimDevice object, then use {@link
* #createDouble(String, Direction, double)} or similar to define the device's fields. See {@link
* edu.wpi.first.wpilibj.ADXRS450_Gyro} for an example implementation.
*/
public class SimDevice implements AutoCloseable {
public enum Direction {
kInput(SimDeviceJNI.kInput),
Expand Down
Expand Up @@ -7,13 +7,17 @@
import edu.wpi.first.hal.JNIWrapper;

public class RoboRioDataJNI extends JNIWrapper {
@SuppressWarnings("AbbreviationAsWordInName")
public static native int registerFPGAButtonCallback(
NotifyCallback callback, boolean initialNotify);

@SuppressWarnings("AbbreviationAsWordInName")
public static native void cancelFPGAButtonCallback(int uid);

@SuppressWarnings("AbbreviationAsWordInName")
public static native boolean getFPGAButton();

@SuppressWarnings("AbbreviationAsWordInName")
public static native void setFPGAButton(boolean fPGAButton);

public static native int registerVInVoltageCallback(
Expand Down
Expand Up @@ -29,6 +29,7 @@ public static native int registerSimDeviceFreedCallback(
public static native int getSimValueDeviceHandle(int handle);

public static class SimDeviceInfo {
@SuppressWarnings("JavadocMethod")
public SimDeviceInfo(String name, int handle) {
this.name = name;
this.handle = handle;
Expand Down Expand Up @@ -62,6 +63,7 @@ public static native int registerSimValueChangedCallback2(
public static native int getSimValueHandle(int device, String name);

public static class SimValueInfo {
@SuppressWarnings("JavadocMethod")
public SimValueInfo(
String name, int handle, int direction, int type, long value1, double value2) {
this.name = name;
Expand Down
2 changes: 0 additions & 2 deletions styleguide/suppressions.xml
Expand Up @@ -3,8 +3,6 @@
suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN"
"http://www.puppycrawl.com/dtds/suppressions_1_1.dtd">
<suppressions>
<suppress files=".*sim.*"
checks="(LineLength|EmptyLineSeparator|ParameterName|ImportOrder|AbbreviationAsWordInName|JavadocMethod|NoFinalizer)" />
<suppress files=".*test.*" checks="MissingJavadocMethod" />
<suppress files=".*wpilibjIntegrationTests.*"
checks="MissingJavadocMethod" />
Expand Down
8 changes: 8 additions & 0 deletions wpilibc/src/main/native/cpp/simulation/SimDeviceSim.cpp
Expand Up @@ -20,6 +20,14 @@ hal::SimValue SimDeviceSim::GetValue(const char* name) const {
return HALSIM_GetSimValueHandle(m_handle, name);
}

hal::SimInt SimDeviceSim::GetInt(const char* name) const {
return HALSIM_GetSimValueHandle(m_handle, name);
}

hal::SimLong SimDeviceSim::GetLong(const char* name) const {
return HALSIM_GetSimValueHandle(m_handle, name);
}

hal::SimDouble SimDeviceSim::GetDouble(const char* name) const {
return HALSIM_GetSimValueHandle(m_handle, name);
}
Expand Down
105 changes: 98 additions & 7 deletions wpilibc/src/main/native/include/frc/simulation/AddressableLEDSim.h
Expand Up @@ -52,39 +52,130 @@ class AddressableLEDSim {
*/
static AddressableLEDSim CreateForIndex(int index);

std::unique_ptr<CallbackStore> RegisterInitializedCallback(
/**
* Register a callback on the Initialized property.
*
* @param callback the callback that will be called whenever the Initialized
* property is changed
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object storing this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
NotifyCallback callback, bool initialNotify);

/**
* Check if initialized.
*
* @return true if initialized
*/
bool GetInitialized() const;

/**
* Change the Initialized value of the LED strip.
*
* @param initialized the new value
*/
void SetInitialized(bool initialized);

std::unique_ptr<CallbackStore> RegisterOutputPortCallback(
/**
* Register a callback on the output port.
*
* @param callback the callback that will be called whenever the output port
* is changed
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterOutputPortCallback(
NotifyCallback callback, bool initialNotify);

/**
* Get the output port.
*
* @return the output port
*/
int GetOutputPort() const;

/**
* Change the output port.
*
* @param outputPort the new output port
*/
void SetOutputPort(int outputPort);

std::unique_ptr<CallbackStore> RegisterLengthCallback(NotifyCallback callback,
bool initialNotify);
/**
* Register a callback on the length.
*
* @param callback the callback that will be called whenever the length is
* changed
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterLengthCallback(
NotifyCallback callback, bool initialNotify);

/**
* Get the length of the LED strip.
*
* @return the length
*/
int GetLength() const;

/**
* Change the length of the LED strip.
*
* @param length the new value
*/
void SetLength(int length);

std::unique_ptr<CallbackStore> RegisterRunningCallback(
/**
* Register a callback on whether the LEDs are running.
*
* @param callback the callback that will be called whenever the LED state is
* changed
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterRunningCallback(
NotifyCallback callback, bool initialNotify);

/**
* Check if the LEDs are running.
*
* @return true if they are
*/
int GetRunning() const;

/**
* Change whether the LEDs are active.
*
* @param running the new value
*/
void SetRunning(bool running);

std::unique_ptr<CallbackStore> RegisterDataCallback(NotifyCallback callback,
bool initialNotify);
/**
* Register a callback on the LED data.
*
* @param callback the callback that will be called whenever the LED data is
* changed
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterDataCallback(
NotifyCallback callback, bool initialNotify);

/**
* Get the LED data.
*
* @param data output parameter to fill with LED data
* @return the length of the LED data
*/
int GetData(struct HAL_AddressableLEDData* data) const;

/**
* Change the LED data.
*
* @param data the new data
* @param length the length of the LED data
*/
void SetData(struct HAL_AddressableLEDData* data, int length);

private:
Expand Down
Expand Up @@ -28,7 +28,7 @@ class AnalogEncoderSim {
explicit AnalogEncoderSim(const AnalogEncoder& encoder);

/**
* Set the position using an {@link Rotation2d}.
* Set the position using an Rotation2d.
*
* @param angle The angle.
*/
Expand All @@ -47,7 +47,7 @@ class AnalogEncoderSim {
units::turn_t GetTurns();

/**
* Get the position as a {@link Rotation2d}.
* Get the position as a Rotation2d.
*/
Rotation2d GetPosition();

Expand Down
65 changes: 60 additions & 5 deletions wpilibc/src/main/native/include/frc/simulation/AnalogGyroSim.h
Expand Up @@ -33,27 +33,82 @@ class AnalogGyroSim {
*/
explicit AnalogGyroSim(int channel);

std::unique_ptr<CallbackStore> RegisterAngleCallback(NotifyCallback callback,
bool initialNotify);
/**
* Register a callback on the angle.
*
* @param callback the callback that will be called whenever the angle changes
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterAngleCallback(
NotifyCallback callback, bool initialNotify);

/**
* Get the current angle of the gyro.
*
* @return the angle measured by the gyro
*/
double GetAngle() const;

/**
* Change the angle measured by the gyro.
*
* @param angle the new value
*/
void SetAngle(double angle);

std::unique_ptr<CallbackStore> RegisterRateCallback(NotifyCallback callback,
bool initialNotify);
/**
* Register a callback on the rate.
*
* @param callback the callback that will be called whenever the rate changes
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterRateCallback(
NotifyCallback callback, bool initialNotify);

/**
* Get the rate of angle change on this gyro.
*
* @return the rate
*/
double GetRate() const;

/**
* Change the rate of the gyro.
*
* @param rate the new rate
*/
void SetRate(double rate);

std::unique_ptr<CallbackStore> RegisterInitializedCallback(
/**
* Register a callback on whether the gyro is initialized.
*
* @param callback the callback that will be called whenever the gyro is
* initialized
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
NotifyCallback callback, bool initialNotify);

/**
* Check if the gyro is initialized.
*
* @return true if initialized
*/
bool GetInitialized() const;

/**
* Set whether this gyro is initialized.
*
* @param initialized the new value
*/
void SetInitialized(bool initialized);

/**
* Reset all simulation data for this object.
*/
void ResetData();

private:
Expand Down