[wpilib][hal] PWM Raw using microseconds (#5283)

Co-authored-by: Joe <sciencewhiz@users.noreply.github.com>
This commit is contained in:
Thad House
2023-06-22 19:43:16 -07:00
committed by GitHub
parent 1fca519fb4
commit c1a01569b4
56 changed files with 374 additions and 466 deletions

View File

@@ -21,10 +21,10 @@ TEST_P(DutyCycleTest, DutyCycle) {
ASSERT_EQ(0, status);
// Ensure our PWM is disabled, and set up properly
HAL_SetPWMRaw(pwmHandle, 0, &status);
HAL_SetPWMPulseTimeMicroseconds(pwmHandle, 0, &status);
ASSERT_EQ(0, status);
HAL_SetPWMConfig(pwmHandle, 2.0, 1.0, 1.0, 0, 0, &status);
HAL_SetPWMConfig(pwmHandle, 5.05, 2.525, 2.525, 2.525, 0, &status);
HAL_SetPWMConfigMicroseconds(pwmHandle, 2000, 1000, 1000, 0, 0, &status);
HAL_SetPWMConfigMicroseconds(pwmHandle, 5050, 2525, 2525, 2525, 0, &status);
ASSERT_EQ(0, status);
HAL_SetPWMPeriodScale(pwmHandle, 0, &status);
ASSERT_EQ(0, status);
@@ -41,8 +41,9 @@ TEST_P(DutyCycleTest, DutyCycle) {
// Sleep enough time for the frequency to converge
usleep(3500000);
ASSERT_NEAR(1000 / 5.05,
(double)HAL_GetDutyCycleFrequency(dutyCycle, &status), 1);
ASSERT_NEAR(
1000 / 5.05,
static_cast<double>(HAL_GetDutyCycleFrequency(dutyCycle, &status)), 1);
// TODO measure output
}

View File

@@ -32,8 +32,8 @@ void TestTimingDMA(int squelch, std::pair<int, int> param) {
ASSERT_EQ(0, status);
// Ensure our PWM is disabled, and set up properly
HAL_SetPWMRaw(pwmHandle, 0, &status);
HAL_SetPWMConfig(pwmHandle, 2.0, 1.0, 1.0, 0, 0, &status);
HAL_SetPWMPulseTimeMicroseconds(pwmHandle, 0, &status);
HAL_SetPWMConfigMicroseconds(pwmHandle, 2000, 1000, 1000, 0, 0, &status);
HAL_SetPWMPeriodScale(pwmHandle, squelch, &status);
unsigned int checkPeriod = 0;
@@ -163,8 +163,8 @@ void TestTiming(int squelch, std::pair<int, int> param) {
ASSERT_NE(pwmHandle, HAL_kInvalidHandle);
// Ensure our PWM is disabled, and set up properly
HAL_SetPWMRaw(pwmHandle, 0, &status);
HAL_SetPWMConfig(pwmHandle, 2.0, 1.0, 1.0, 0, 0, &status);
HAL_SetPWMPulseTimeMicroseconds(pwmHandle, 0, &status);
HAL_SetPWMConfigMicroseconds(pwmHandle, 2000, 1000, 1000, 0, 0, &status);
HAL_SetPWMPeriodScale(pwmHandle, squelch, &status);
unsigned int checkPeriod = 0;
@@ -251,7 +251,7 @@ void TestTiming(int squelch, std::pair<int, int> param) {
}
}
HAL_SetPWMRaw(pwmHandle, 0, &status);
HAL_SetPWMPulseTimeMicroseconds(pwmHandle, 0, &status);
// Ensure our interrupts have the proper counts
ASSERT_EQ(interruptData.risingStamps.size(),

View File

@@ -15,18 +15,18 @@ public class PWMConfigDataResult {
this.min = min;
}
/** The maximum PWM value. */
/** The maximum PWM value in microseconds. */
public int max;
/** The deadband maximum PWM value. */
/** The deadband maximum PWM value in microseconds. */
public int deadbandMax;
/** The center PWM value. */
/** The center PWM value in microseconds. */
public int center;
/** The deadband minimum PWM value. */
/** The deadband minimum PWM value in microseconds. */
public int deadbandMin;
/** The minimum PWM value. */
/** The minimum PWM value in microseconds. */
public int min;
}

View File

@@ -11,7 +11,7 @@ public class PWMJNI extends DIOJNI {
public static native void freePWMPort(int pwmPortHandle);
public static native void setPWMConfigRaw(
public static native void setPWMConfigMicroseconds(
int pwmPortHandle,
int maxPwm,
int deadbandMaxPwm,
@@ -19,27 +19,19 @@ public class PWMJNI extends DIOJNI {
int deadbandMinPwm,
int minPwm);
public static native void setPWMConfig(
int pwmPortHandle,
double maxPwm,
double deadbandMaxPwm,
double centerPwm,
double deadbandMinPwm,
double minPwm);
public static native PWMConfigDataResult getPWMConfigRaw(int pwmPortHandle);
public static native PWMConfigDataResult getPWMConfigMicroseconds(int pwmPortHandle);
public static native void setPWMEliminateDeadband(int pwmPortHandle, boolean eliminateDeadband);
public static native boolean getPWMEliminateDeadband(int pwmPortHandle);
public static native void setPWMRaw(int pwmPortHandle, short value);
public static native void setPulseTimeMicroseconds(int pwmPortHandle, int microsecondPulseTime);
public static native void setPWMSpeed(int pwmPortHandle, double speed);
public static native void setPWMPosition(int pwmPortHandle, double position);
public static native short getPWMRaw(int pwmPortHandle);
public static native int getPulseTimeMicroseconds(int pwmPortHandle);
public static native double getPWMSpeed(int pwmPortHandle);
@@ -49,5 +41,7 @@ public class PWMJNI extends DIOJNI {
public static native void latchPWMZero(int pwmPortHandle);
public static native void setAlwaysHighMode(int pwmPortHandle);
public static native void setPWMPeriodScale(int pwmPortHandle, int squelchMask);
}

View File

@@ -16,14 +16,14 @@ public class PWMDataJNI extends JNIWrapper {
public static native void setInitialized(int index, boolean initialized);
public static native int registerRawValueCallback(
public static native int registerPulseMicrosecondCallback(
int index, NotifyCallback callback, boolean initialNotify);
public static native void cancelRawValueCallback(int index, int uid);
public static native void cancelPulseMicrosecondCallback(int index, int uid);
public static native int getRawValue(int index);
public static native int getPulseMicrosecond(int index);
public static native void setRawValue(int index, int rawValue);
public static native void setPulseMicrosecond(int index, int microsecondPulseTime);
public static native int registerSpeedCallback(
int index, NotifyCallback callback, boolean initialNotify);

View File

@@ -112,9 +112,7 @@ void initializeDigital(int32_t* status) {
pwmSystem->writeConfig_Period(std::lround(kDefaultPwmPeriod / loopTime),
status);
uint16_t minHigh = std::lround(
(kDefaultPwmCenter - kDefaultPwmStepsDown * loopTime) / loopTime);
pwmSystem->writeConfig_MinHigh(minHigh, status);
pwmSystem->writeConfig_MinHigh(0, status);
// Ensure that PWM output values are set to OFF
for (uint8_t pwmIndex = 0; pwmIndex < kNumPWMChannels; pwmIndex++) {
// Copy of SetPWM

View File

@@ -47,15 +47,8 @@ constexpr int32_t kExpectedLoopTiming = 40;
* devices.
*/
constexpr double kDefaultPwmPeriod = 5.05;
/**
* kDefaultPwmCenter is the PWM range center in ms
*/
constexpr double kDefaultPwmCenter = 1.5;
/**
* kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
*/
constexpr int32_t kDefaultPwmStepsDown = 1000;
constexpr int32_t kPwmDisabled = 0;
constexpr int32_t kPwmAlwaysHigh = 0xFFFF;
extern std::unique_ptr<tDIO> digitalSystem;
extern std::unique_ptr<tRelay> relaySystem;

View File

@@ -9,6 +9,8 @@
#include <cstdio>
#include <thread>
#include <fmt/format.h>
#include "ConstantsInternal.h"
#include "DigitalInternal.h"
#include "HALInitializer.h"
@@ -118,7 +120,7 @@ HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
}
// Defaults to allow an always valid config.
HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
HAL_SetPWMConfigMicroseconds(handle, 2000, 1501, 1500, 1499, 1000, status);
port->previousAllocation = allocationLocation ? allocationLocation : "";
@@ -158,62 +160,28 @@ HAL_Bool HAL_CheckPWMChannel(int32_t channel) {
return channel < kNumPWMChannels && channel >= 0;
}
void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double max,
double deadbandMax, double center, double deadbandMin,
double min, int32_t* status) {
void HAL_SetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle, int32_t max,
int32_t deadbandMax, int32_t center,
int32_t deadbandMin, int32_t min,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
// calculate the loop time in milliseconds
double loopTime =
HAL_GetPWMLoopTiming(status) / (kSystemClockTicksPerMicrosecond * 1e3);
if (*status != 0) {
return;
}
int32_t maxPwm = static_cast<int32_t>((max - kDefaultPwmCenter) / loopTime +
kDefaultPwmStepsDown - 1);
int32_t deadbandMaxPwm = static_cast<int32_t>(
(deadbandMax - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t centerPwm = static_cast<int32_t>(
(center - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t deadbandMinPwm = static_cast<int32_t>(
(deadbandMin - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t minPwm = static_cast<int32_t>((min - kDefaultPwmCenter) / loopTime +
kDefaultPwmStepsDown - 1);
port->maxPwm = maxPwm;
port->deadbandMaxPwm = deadbandMaxPwm;
port->deadbandMinPwm = deadbandMinPwm;
port->centerPwm = centerPwm;
port->minPwm = minPwm;
port->maxPwm = max;
port->deadbandMaxPwm = deadbandMax;
port->deadbandMinPwm = deadbandMin;
port->centerPwm = center;
port->minPwm = min;
port->configSet = true;
}
void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
int32_t deadbandMaxPwm, int32_t centerPwm,
int32_t deadbandMinPwm, int32_t minPwm,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
port->maxPwm = maxPwm;
port->deadbandMaxPwm = deadbandMaxPwm;
port->deadbandMinPwm = deadbandMinPwm;
port->centerPwm = centerPwm;
port->minPwm = minPwm;
}
void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
int32_t* deadbandMaxPwm, int32_t* centerPwm,
int32_t* deadbandMinPwm, int32_t* minPwm,
int32_t* status) {
void HAL_GetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* maxPwm, int32_t* deadbandMaxPwm,
int32_t* centerPwm, int32_t* deadbandMinPwm,
int32_t* minPwm, int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
@@ -246,18 +214,30 @@ HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
return port->eliminateDeadband;
}
void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
int32_t* status) {
void HAL_SetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t microsecondPulseTime,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
if (microsecondPulseTime < 0 ||
(microsecondPulseTime != 0xFFFF && microsecondPulseTime >= 4096)) {
*status = PARAMETER_OUT_OF_RANGE;
hal::SetLastError(
status,
fmt::format("Pulse time {} out of range. Expect [0-4096) or 0xFFFF",
microsecondPulseTime));
return;
}
if (port->channel < tPWM::kNumHdrRegisters) {
pwmSystem->writeHdr(port->channel, value, status);
pwmSystem->writeHdr(port->channel, microsecondPulseTime, status);
} else {
pwmSystem->writeMXP(port->channel - tPWM::kNumHdrRegisters, value, status);
pwmSystem->writeMXP(port->channel - tPWM::kNumHdrRegisters,
microsecondPulseTime, status);
}
}
@@ -302,7 +282,7 @@ void HAL_SetPWMSpeed(HAL_DigitalHandle pwmPortHandle, double speed,
return;
}
HAL_SetPWMRaw(pwmPortHandle, rawValue, status);
HAL_SetPWMPulseTimeMicroseconds(pwmPortHandle, rawValue, status);
}
void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double pos,
@@ -335,14 +315,15 @@ void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double pos,
return;
}
HAL_SetPWMRaw(pwmPortHandle, rawValue, status);
HAL_SetPWMPulseTimeMicroseconds(pwmPortHandle, rawValue, status);
}
void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
HAL_SetPWMRaw(pwmPortHandle, kPwmDisabled, status);
HAL_SetPWMPulseTimeMicroseconds(pwmPortHandle, kPwmDisabled, status);
}
int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
int32_t HAL_GetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
@@ -367,12 +348,11 @@ double HAL_GetPWMSpeed(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
return 0;
}
int32_t value = HAL_GetPWMRaw(pwmPortHandle, status);
int32_t value = HAL_GetPWMPulseTimeMicroseconds(pwmPortHandle, status);
if (*status != 0) {
return 0;
}
DigitalPort* dPort = port.get();
if (value == kPwmDisabled) {
return 0.0;
} else if (value > GetMaxPositivePwm(dPort)) {
@@ -401,7 +381,7 @@ double HAL_GetPWMPosition(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
return 0;
}
int32_t value = HAL_GetPWMRaw(pwmPortHandle, status);
int32_t value = HAL_GetPWMPulseTimeMicroseconds(pwmPortHandle, status);
if (*status != 0) {
return 0;
}
@@ -444,6 +424,11 @@ void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
}
}
void HAL_SetPWMAlwaysHighMode(HAL_DigitalHandle pwmPortHandle,
int32_t* status) {
HAL_SetPWMPulseTimeMicroseconds(pwmPortHandle, kPwmAlwaysHigh, status);
}
int32_t HAL_GetPWMLoopTiming(int32_t* status) {
initializeDigital(status);
if (*status != 0) {

View File

@@ -13,7 +13,7 @@ void HALSIM_ResetPWMData(int32_t index) {}
HAL_SIMDATAVALUE_STUB_CAPI(TYPE, HALSIM, PWM##CAPINAME, RETURN)
DEFINE_CAPI(HAL_Bool, Initialized, false)
DEFINE_CAPI(int32_t, RawValue, 0)
DEFINE_CAPI(int32_t, PulseMicrosecond, 0)
DEFINE_CAPI(double, Speed, 0)
DEFINE_CAPI(double, Position, 0)
DEFINE_CAPI(int32_t, PeriodScale, 0)

View File

@@ -63,43 +63,27 @@ Java_edu_wpi_first_hal_PWMJNI_freePWMPort
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: setPWMConfigRaw
* Method: setPWMConfigMicroseconds
* Signature: (IIIIII)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_PWMJNI_setPWMConfigRaw
Java_edu_wpi_first_hal_PWMJNI_setPWMConfigMicroseconds
(JNIEnv* env, jclass, jint id, jint maxPwm, jint deadbandMaxPwm,
jint centerPwm, jint deadbandMinPwm, jint minPwm)
{
int32_t status = 0;
HAL_SetPWMConfigRaw((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
deadbandMinPwm, minPwm, &status);
HAL_SetPWMConfigMicroseconds((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm,
centerPwm, deadbandMinPwm, minPwm, &status);
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: setPWMConfig
* Signature: (IDDDDD)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_PWMJNI_setPWMConfig
(JNIEnv* env, jclass, jint id, jdouble maxPwm, jdouble deadbandMaxPwm,
jdouble centerPwm, jdouble deadbandMinPwm, jdouble minPwm)
{
int32_t status = 0;
HAL_SetPWMConfig((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
deadbandMinPwm, minPwm, &status);
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: getPWMConfigRaw
* Method: getPWMConfigMicroseconds
* Signature: (I)Ljava/lang/Object;
*/
JNIEXPORT jobject JNICALL
Java_edu_wpi_first_hal_PWMJNI_getPWMConfigRaw
Java_edu_wpi_first_hal_PWMJNI_getPWMConfigMicroseconds
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
@@ -108,8 +92,8 @@ Java_edu_wpi_first_hal_PWMJNI_getPWMConfigRaw
int32_t centerPwm = 0;
int32_t deadbandMinPwm = 0;
int32_t minPwm = 0;
HAL_GetPWMConfigRaw((HAL_DigitalHandle)id, &maxPwm, &deadbandMaxPwm,
&centerPwm, &deadbandMinPwm, &minPwm, &status);
HAL_GetPWMConfigMicroseconds((HAL_DigitalHandle)id, &maxPwm, &deadbandMaxPwm,
&centerPwm, &deadbandMinPwm, &minPwm, &status);
CheckStatus(env, status);
return CreatePWMConfigDataResult(env, maxPwm, deadbandMaxPwm, centerPwm,
deadbandMinPwm, minPwm);
@@ -146,15 +130,15 @@ Java_edu_wpi_first_hal_PWMJNI_getPWMEliminateDeadband
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: setPWMRaw
* Signature: (IS)V
* Method: setPulseTimeMicroseconds
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_PWMJNI_setPWMRaw
(JNIEnv* env, jclass, jint id, jshort value)
Java_edu_wpi_first_hal_PWMJNI_setPulseTimeMicroseconds
(JNIEnv* env, jclass, jint id, jint value)
{
int32_t status = 0;
HAL_SetPWMRaw((HAL_DigitalHandle)id, value, &status);
HAL_SetPWMPulseTimeMicroseconds((HAL_DigitalHandle)id, value, &status);
CheckStatus(env, status);
}
@@ -188,15 +172,16 @@ Java_edu_wpi_first_hal_PWMJNI_setPWMPosition
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: getPWMRaw
* Signature: (I)S
* Method: getPulseTimeMicroseconds
* Signature: (I)I
*/
JNIEXPORT jshort JNICALL
Java_edu_wpi_first_hal_PWMJNI_getPWMRaw
JNIEXPORT jint JNICALL
Java_edu_wpi_first_hal_PWMJNI_getPulseTimeMicroseconds
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
jshort returnValue = HAL_GetPWMRaw((HAL_DigitalHandle)id, &status);
int32_t returnValue =
HAL_GetPWMPulseTimeMicroseconds((HAL_DigitalHandle)id, &status);
CheckStatus(env, status);
return returnValue;
}
@@ -259,6 +244,20 @@ Java_edu_wpi_first_hal_PWMJNI_latchPWMZero
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: setAlwaysHighMode
* Signature: (I)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_PWMJNI_setAlwaysHighMode
(JNIEnv* env, jclass, jint id)
{
int32_t status = 0;
HAL_SetPWMAlwaysHighMode((HAL_DigitalHandle)id, &status);
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_hal_PWMJNI
* Method: setPWMPeriodScale

View File

@@ -64,52 +64,52 @@ Java_edu_wpi_first_hal_simulation_PWMDataJNI_setInitialized
/*
* Class: edu_wpi_first_hal_simulation_PWMDataJNI
* Method: registerRawValueCallback
* Method: registerPulseMicrosecondCallback
* Signature: (ILjava/lang/Object;Z)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_hal_simulation_PWMDataJNI_registerRawValueCallback
Java_edu_wpi_first_hal_simulation_PWMDataJNI_registerPulseMicrosecondCallback
(JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
{
return sim::AllocateCallback(env, index, callback, initialNotify,
&HALSIM_RegisterPWMRawValueCallback);
&HALSIM_RegisterPWMPulseMicrosecondCallback);
}
/*
* Class: edu_wpi_first_hal_simulation_PWMDataJNI
* Method: cancelRawValueCallback
* Method: cancelPulseMicrosecondCallback
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_PWMDataJNI_cancelRawValueCallback
Java_edu_wpi_first_hal_simulation_PWMDataJNI_cancelPulseMicrosecondCallback
(JNIEnv* env, jclass, jint index, jint handle)
{
return sim::FreeCallback(env, handle, index,
&HALSIM_CancelPWMRawValueCallback);
&HALSIM_CancelPWMPulseMicrosecondCallback);
}
/*
* Class: edu_wpi_first_hal_simulation_PWMDataJNI
* Method: getRawValue
* Method: getPulseMicrosecond
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_hal_simulation_PWMDataJNI_getRawValue
Java_edu_wpi_first_hal_simulation_PWMDataJNI_getPulseMicrosecond
(JNIEnv*, jclass, jint index)
{
return HALSIM_GetPWMRawValue(index);
return HALSIM_GetPWMPulseMicrosecond(index);
}
/*
* Class: edu_wpi_first_hal_simulation_PWMDataJNI
* Method: setRawValue
* Method: setPulseMicrosecond
* Signature: (II)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_PWMDataJNI_setRawValue
Java_edu_wpi_first_hal_simulation_PWMDataJNI_setPulseMicrosecond
(JNIEnv*, jclass, jint index, jint value)
{
HALSIM_SetPWMRawValue(index, value);
HALSIM_SetPWMPulseMicrosecond(index, value);
}
/*

View File

@@ -50,7 +50,7 @@ HAL_Bool HAL_CheckPWMChannel(int32_t channel);
/**
* Sets the configuration settings for the PWM channel.
*
* All values are in milliseconds.
* All values are in microseconds.
*
* @param[in] pwmPortHandle the PWM handle
* @param[in] maxPwm the maximum PWM value
@@ -60,17 +60,15 @@ HAL_Bool HAL_CheckPWMChannel(int32_t channel);
* @param[in] minPwm the minimum PWM value
* @param[out] status Error status variable. 0 on success.
*/
void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double maxPwm,
double deadbandMaxPwm, double centerPwm,
double deadbandMinPwm, double minPwm, int32_t* status);
void HAL_SetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t maxPwm, int32_t deadbandMaxPwm,
int32_t centerPwm, int32_t deadbandMinPwm,
int32_t minPwm, int32_t* status);
/**
* Sets the raw configuration settings for the PWM channel.
* Gets the pwm configuration settings for the PWM channel.
*
* We recommend using HAL_SetPWMConfig() instead, as those values are properly
* scaled. Usually used for values grabbed by HAL_GetPWMConfigRaw().
*
* Values are in raw FPGA units.
* Values are in microseconds.
*
* @param[in] pwmPortHandle the PWM handle
* @param[in] maxPwm the maximum PWM value
@@ -80,29 +78,10 @@ void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double maxPwm,
* @param[in] minPwm the minimum PWM value
* @param[out] status Error status variable. 0 on success.
*/
void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
int32_t deadbandMaxPwm, int32_t centerPwm,
int32_t deadbandMinPwm, int32_t minPwm,
int32_t* status);
/**
* Gets the raw pwm configuration settings for the PWM channel.
*
* Values are in raw FPGA units. These units have the potential to change for
* any FPGA release.
*
* @param[in] pwmPortHandle the PWM handle
* @param[in] maxPwm the maximum PWM value
* @param[in] deadbandMaxPwm the high range of the center deadband
* @param[in] centerPwm the center PWM value
* @param[in] deadbandMinPwm the low range of the center deadband
* @param[in] minPwm the minimum PWM value
* @param[out] status Error status variable. 0 on success.
*/
void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
int32_t* deadbandMaxPwm, int32_t* centerPwm,
int32_t* deadbandMinPwm, int32_t* minPwm,
int32_t* status);
void HAL_GetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* maxPwm, int32_t* deadbandMaxPwm,
int32_t* centerPwm, int32_t* deadbandMinPwm,
int32_t* minPwm, int32_t* status);
/**
* Sets if the FPGA should output the center value if the input value is within
@@ -126,17 +105,16 @@ HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
int32_t* status);
/**
* Sets a PWM channel to the desired value.
* Sets a PWM channel to the desired pulse width in microseconds.
*
* The values are in raw FPGA units, and have the potential to change with any
* FPGA release.
*
* @param[in] pwmPortHandle the PWM handle
* @param[in] value the PWM value to set
* @param[in] microsecondPulseTime the PWM value to set
* @param[out] status Error status variable. 0 on success.
*/
void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
int32_t* status);
void HAL_SetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t microsecondPulseTime,
int32_t* status);
/**
* Sets a PWM channel to the desired scaled value.
@@ -177,16 +155,14 @@ void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double position,
void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status);
/**
* Gets a value from a PWM channel.
*
* The values are in raw FPGA units, and have the potential to change with any
* FPGA release.
* Gets the current microsecond pulse time from a PWM channel.
*
* @param[in] pwmPortHandle the PWM handle
* @param[out] status Error status variable. 0 on success.
* @return the current raw PWM value
* @return the current PWM microsecond pulse time
*/
int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status);
int32_t HAL_GetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* status);
/**
* Gets a scaled value from a PWM channel.
@@ -228,6 +204,14 @@ void HAL_LatchPWMZero(HAL_DigitalHandle pwmPortHandle, int32_t* status);
void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
int32_t* status);
/**
* Sets the PWM output to be a continous high signal while enabled.
*
* @param[in] pwmPortHandle the PWM handle.
* @param[out] status Error status variable. 0 on success.
*/
void HAL_SetPWMAlwaysHighMode(HAL_DigitalHandle pwmPortHandle, int32_t* status);
/**
* Gets the loop timing of the PWM system.
*

View File

@@ -20,12 +20,13 @@ void HALSIM_CancelPWMInitializedCallback(int32_t index, int32_t uid);
HAL_Bool HALSIM_GetPWMInitialized(int32_t index);
void HALSIM_SetPWMInitialized(int32_t index, HAL_Bool initialized);
int32_t HALSIM_RegisterPWMRawValueCallback(int32_t index,
HAL_NotifyCallback callback,
void* param, HAL_Bool initialNotify);
void HALSIM_CancelPWMRawValueCallback(int32_t index, int32_t uid);
int32_t HALSIM_GetPWMRawValue(int32_t index);
void HALSIM_SetPWMRawValue(int32_t index, int32_t rawValue);
int32_t HALSIM_RegisterPWMPulseMicrosecondCallback(int32_t index,
HAL_NotifyCallback callback,
void* param,
HAL_Bool initialNotify);
void HALSIM_CancelPWMPulseMicrosecondCallback(int32_t index, int32_t uid);
int32_t HALSIM_GetPWMPulseMicrosecond(int32_t index);
void HALSIM_SetPWMPulseMicrosecond(int32_t index, int32_t microsecondPulseTime);
int32_t HALSIM_RegisterPWMSpeedCallback(int32_t index,
HAL_NotifyCallback callback,

View File

@@ -39,14 +39,6 @@ constexpr int32_t kExpectedLoopTiming = 40;
* devices.
*/
constexpr float kDefaultPwmPeriod = 5.05f;
/**
* kDefaultPwmCenter is the PWM range center in ms
*/
constexpr float kDefaultPwmCenter = 1.5f;
/**
* kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
*/
constexpr int32_t kDefaultPwmStepsDown = 1000;
constexpr int32_t kPwmDisabled = 0;
struct DigitalPort {

View File

@@ -62,7 +62,7 @@ HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
SimPWMData[origChannel].initialized = true;
// Defaults to allow an always valid config.
HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
HAL_SetPWMConfigMicroseconds(handle, 2000, 1501, 1500, 1499, 1000, status);
port->previousAllocation = allocationLocation ? allocationLocation : "";
@@ -84,62 +84,28 @@ HAL_Bool HAL_CheckPWMChannel(int32_t channel) {
return channel < kNumPWMChannels && channel >= 0;
}
void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double max,
double deadbandMax, double center, double deadbandMin,
double min, int32_t* status) {
void HAL_SetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle, int32_t max,
int32_t deadbandMax, int32_t center,
int32_t deadbandMin, int32_t min,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
// calculate the loop time in milliseconds
double loopTime =
HAL_GetPWMLoopTiming(status) / (kSystemClockTicksPerMicrosecond * 1e3);
if (*status != 0) {
return;
}
int32_t maxPwm = static_cast<int32_t>((max - kDefaultPwmCenter) / loopTime +
kDefaultPwmStepsDown - 1);
int32_t deadbandMaxPwm = static_cast<int32_t>(
(deadbandMax - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t centerPwm = static_cast<int32_t>(
(center - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t deadbandMinPwm = static_cast<int32_t>(
(deadbandMin - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
int32_t minPwm = static_cast<int32_t>((min - kDefaultPwmCenter) / loopTime +
kDefaultPwmStepsDown - 1);
port->maxPwm = maxPwm;
port->deadbandMaxPwm = deadbandMaxPwm;
port->deadbandMinPwm = deadbandMinPwm;
port->centerPwm = centerPwm;
port->minPwm = minPwm;
port->maxPwm = max;
port->deadbandMaxPwm = deadbandMax;
port->deadbandMinPwm = deadbandMin;
port->centerPwm = center;
port->minPwm = min;
port->configSet = true;
}
void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
int32_t deadbandMaxPwm, int32_t centerPwm,
int32_t deadbandMinPwm, int32_t minPwm,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
port->maxPwm = maxPwm;
port->deadbandMaxPwm = deadbandMaxPwm;
port->deadbandMinPwm = deadbandMinPwm;
port->centerPwm = centerPwm;
port->minPwm = minPwm;
}
void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
int32_t* deadbandMaxPwm, int32_t* centerPwm,
int32_t* deadbandMinPwm, int32_t* minPwm,
int32_t* status) {
void HAL_GetPWMConfigMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* maxPwm, int32_t* deadbandMaxPwm,
int32_t* centerPwm, int32_t* deadbandMinPwm,
int32_t* minPwm, int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
@@ -172,15 +138,15 @@ HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
return port->eliminateDeadband;
}
void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
int32_t* status) {
void HAL_SetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t value, int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
SimPWMData[port->channel].rawValue = value;
SimPWMData[port->channel].pulseMicrosecond = value;
}
void HAL_SetPWMSpeed(HAL_DigitalHandle pwmPortHandle, double speed,
@@ -231,19 +197,20 @@ void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
*status = HAL_HANDLE_ERROR;
return;
}
SimPWMData[port->channel].rawValue = 0;
SimPWMData[port->channel].pulseMicrosecond = 0;
SimPWMData[port->channel].position = 0;
SimPWMData[port->channel].speed = 0;
}
int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
int32_t HAL_GetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return 0;
}
return SimPWMData[port->channel].rawValue;
return SimPWMData[port->channel].pulseMicrosecond;
}
double HAL_GetPWMSpeed(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
@@ -299,6 +266,19 @@ void HAL_LatchPWMZero(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
SimPWMData[port->channel].zeroLatch = false;
}
void HAL_SetPWMAlwaysHighMode(HAL_DigitalHandle pwmPortHandle,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
SimPWMData[port->channel].pulseMicrosecond = 0xFFFF;
SimPWMData[port->channel].position = 0xFFFF;
SimPWMData[port->channel].speed = 0xFFFF;
}
void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
int32_t* status) {
auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);

View File

@@ -17,7 +17,7 @@ void InitializePWMData() {
PWMData* hal::SimPWMData;
void PWMData::ResetData() {
initialized.Reset(false);
rawValue.Reset(0);
pulseMicrosecond.Reset(0);
speed.Reset(0);
position.Reset(0);
periodScale.Reset(0);
@@ -34,7 +34,7 @@ void HALSIM_ResetPWMData(int32_t index) {
LOWERNAME)
DEFINE_CAPI(HAL_Bool, Initialized, initialized)
DEFINE_CAPI(int32_t, RawValue, rawValue)
DEFINE_CAPI(int32_t, PulseMicrosecond, pulseMicrosecond)
DEFINE_CAPI(double, Speed, speed)
DEFINE_CAPI(double, Position, position)
DEFINE_CAPI(int32_t, PeriodScale, periodScale)
@@ -46,7 +46,7 @@ DEFINE_CAPI(HAL_Bool, ZeroLatch, zeroLatch)
void HALSIM_RegisterPWMAllCallbacks(int32_t index, HAL_NotifyCallback callback,
void* param, HAL_Bool initialNotify) {
REGISTER(initialized);
REGISTER(rawValue);
REGISTER(pulseMicrosecond);
REGISTER(speed);
REGISTER(position);
REGISTER(periodScale);

View File

@@ -10,7 +10,7 @@
namespace hal {
class PWMData {
HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
HAL_SIMDATAVALUE_DEFINE_NAME(RawValue)
HAL_SIMDATAVALUE_DEFINE_NAME(PulseMicrosecond)
HAL_SIMDATAVALUE_DEFINE_NAME(Speed)
HAL_SIMDATAVALUE_DEFINE_NAME(Position)
HAL_SIMDATAVALUE_DEFINE_NAME(PeriodScale)
@@ -19,7 +19,8 @@ class PWMData {
public:
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
false};
SimDataValue<int32_t, HAL_MakeInt, GetRawValueName> rawValue{0};
SimDataValue<int32_t, HAL_MakeInt, GetPulseMicrosecondName> pulseMicrosecond{
0};
SimDataValue<double, HAL_MakeDouble, GetSpeedName> speed{0};
SimDataValue<double, HAL_MakeDouble, GetPositionName> position{0};
SimDataValue<int32_t, HAL_MakeInt, GetPeriodScaleName> periodScale{0};

View File

@@ -30,7 +30,7 @@ void HALSimWSProviderPWM::RegisterCallbacks() {
m_initCbKey = REGISTER(Initialized, "<init", bool, boolean);
m_speedCbKey = REGISTER(Speed, "<speed", double, double);
m_positionCbKey = REGISTER(Position, "<position", double, double);
m_rawCbKey = REGISTER(RawValue, "<raw", int32_t, int);
m_rawCbKey = REGISTER(PulseMicrosecond, "<raw", int32_t, int);
m_periodScaleCbKey = REGISTER(PeriodScale, "<period_scale", int32_t, int);
m_zeroLatchCbKey = REGISTER(ZeroLatch, "<zero_latch", bool, boolean);
}
@@ -43,7 +43,7 @@ void HALSimWSProviderPWM::DoCancelCallbacks() {
HALSIM_CancelPWMInitializedCallback(m_channel, m_initCbKey);
HALSIM_CancelPWMSpeedCallback(m_channel, m_speedCbKey);
HALSIM_CancelPWMPositionCallback(m_channel, m_positionCbKey);
HALSIM_CancelPWMRawValueCallback(m_channel, m_rawCbKey);
HALSIM_CancelPWMPulseMicrosecondCallback(m_channel, m_rawCbKey);
HALSIM_CancelPWMPeriodScaleCallback(m_channel, m_periodScaleCbKey);
HALSIM_CancelPWMZeroLatchCallback(m_channel, m_zeroLatchCbKey);

View File

@@ -54,18 +54,18 @@ PWM::~PWM() {
FRC_ReportError(status, "Channel {}", m_channel);
}
void PWM::SetRaw(uint16_t value) {
void PWM::SetPulseTime(units::microsecond_t time) {
int32_t status = 0;
HAL_SetPWMRaw(m_handle, value, &status);
HAL_SetPWMPulseTimeMicroseconds(m_handle, time.value(), &status);
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
uint16_t PWM::GetRaw() const {
units::microsecond_t PWM::GetPulseTime() const {
int32_t status = 0;
uint16_t value = HAL_GetPWMRaw(m_handle, &status);
double value = HAL_GetPWMPulseTimeMicroseconds(m_handle, &status);
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
return value;
return units::microsecond_t{value};
}
void PWM::SetPosition(double pos) {
@@ -135,27 +135,37 @@ void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
void PWM::SetBounds(double max, double deadbandMax, double center,
double deadbandMin, double min) {
void PWM::SetBounds(units::microsecond_t max, units::microsecond_t deadbandMax,
units::microsecond_t center,
units::microsecond_t deadbandMin,
units::microsecond_t min) {
int32_t status = 0;
HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
HAL_SetPWMConfigMicroseconds(m_handle, max.value(), deadbandMax.value(),
center.value(), deadbandMin.value(), min.value(),
&status);
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
int min) {
void PWM::GetBounds(units::microsecond_t* max,
units::microsecond_t* deadbandMax,
units::microsecond_t* center,
units::microsecond_t* deadbandMin,
units::microsecond_t* min) {
int32_t status = 0;
HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
int32_t rawMax, rawDeadbandMax, rawCenter, rawDeadbandMin, rawMin;
HAL_GetPWMConfigMicroseconds(m_handle, &rawMax, &rawDeadbandMax, &rawCenter,
&rawDeadbandMin, &rawMin, &status);
*max = units::microsecond_t{static_cast<double>(rawMax)};
*deadbandMax = units::microsecond_t{static_cast<double>(rawDeadbandMax)};
*center = units::microsecond_t{static_cast<double>(rawCenter)};
*deadbandMin = units::microsecond_t{static_cast<double>(rawDeadbandMin)};
*min = units::microsecond_t{static_cast<double>(rawMin)};
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
void PWM::GetRawBounds(int* max, int* deadbandMax, int* center,
int* deadbandMin, int* min) {
void PWM::SetAlwaysHighMode() {
int32_t status = 0;
HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
HAL_SetPWMAlwaysHighMode(m_handle, &status);
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
@@ -168,6 +178,6 @@ void PWM::InitSendable(wpi::SendableBuilder& builder) {
builder.SetActuator(true);
builder.SetSafeState([=, this] { SetDisabled(); });
builder.AddDoubleProperty(
"Value", [=, this] { return GetRaw(); },
[=, this](double value) { SetRaw(value); });
"Value", [=, this] { return GetPulseTime().value(); },
[=, this](double value) { SetPulseTime(units::millisecond_t{value}); });
}

View File

@@ -13,12 +13,12 @@ using namespace frc;
constexpr double Servo::kMaxServoAngle;
constexpr double Servo::kMinServoAngle;
constexpr double Servo::kDefaultMaxServoPWM;
constexpr double Servo::kDefaultMinServoPWM;
constexpr units::millisecond_t Servo::kDefaultMaxServoPWM;
constexpr units::millisecond_t Servo::kDefaultMinServoPWM;
Servo::Servo(int channel) : PWM(channel) {
// Set minimum and maximum PWM values supported by the servo
SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
SetBounds(kDefaultMaxServoPWM, 0.0_ms, 0.0_ms, 0.0_ms, kDefaultMinServoPWM);
// Assign defaults for period multiplier for the servo PWM control signal
SetPeriodMultiplier(kPeriodMultiplier_4X);
@@ -32,7 +32,7 @@ void Servo::Set(double value) {
}
void Servo::SetOffline() {
SetRaw(0);
SetDisabled();
}
double Servo::Get() const {

View File

@@ -9,7 +9,7 @@
using namespace frc;
DMC60::DMC60(int channel) : PWMMotorController("DMC60", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
Jaguar::Jaguar(int channel) : PWMMotorController("Jaguar", channel) {
m_pwm.SetBounds(2.31, 1.55, 1.507, 1.454, 0.697);
m_pwm.SetBounds(2.31_ms, 1.55_ms, 1.507_ms, 1.454_ms, 0.697_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -30,7 +30,7 @@ void NidecBrushless::Set(double speed) {
if (!m_disabled) {
m_speed = speed;
m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
m_pwm.SetRaw(0xffff);
m_pwm.SetAlwaysHighMode();
}
Feed();
}

View File

@@ -10,7 +10,7 @@ using namespace frc;
PWMSparkMax::PWMSparkMax(int channel)
: PWMMotorController("PWMSparkMax", channel) {
m_pwm.SetBounds(2.003, 1.55, 1.50, 1.46, 0.999);
m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -10,7 +10,7 @@ using namespace frc;
PWMTalonFX::PWMTalonFX(int channel)
: PWMMotorController("PWMTalonFX", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -10,7 +10,7 @@ using namespace frc;
PWMTalonSRX::PWMTalonSRX(int channel)
: PWMMotorController("PWMTalonSRX", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
PWMVenom::PWMVenom(int channel) : PWMMotorController("PWMVenom", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -10,7 +10,7 @@ using namespace frc;
PWMVictorSPX::PWMVictorSPX(int channel)
: PWMMotorController("PWMVictorSPX", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
SD540::SD540(int channel) : PWMMotorController("SD540", channel) {
m_pwm.SetBounds(2.05, 1.55, 1.50, 1.44, 0.94);
m_pwm.SetBounds(2.05_ms, 1.55_ms, 1.50_ms, 1.44_ms, 0.94_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
Spark::Spark(int channel) : PWMMotorController("Spark", channel) {
m_pwm.SetBounds(2.003, 1.55, 1.50, 1.46, 0.999);
m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
Talon::Talon(int channel) : PWMMotorController("Talon", channel) {
m_pwm.SetBounds(2.037, 1.539, 1.513, 1.487, 0.989);
m_pwm.SetBounds(2.037_ms, 1.539_ms, 1.513_ms, 1.487_ms, 0.989_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
Victor::Victor(int channel) : PWMMotorController("Victor", channel) {
m_pwm.SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
m_pwm.SetBounds(2.027_ms, 1.525_ms, 1.507_ms, 1.49_ms, 1.026_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_2X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -9,7 +9,7 @@
using namespace frc;
VictorSP::VictorSP(int channel) : PWMMotorController("VictorSP", channel) {
m_pwm.SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
m_pwm.SetSpeed(0.0);
m_pwm.SetZeroLatch();

View File

@@ -39,21 +39,21 @@ void PWMSim::SetInitialized(bool initialized) {
HALSIM_SetPWMInitialized(m_index, initialized);
}
std::unique_ptr<CallbackStore> PWMSim::RegisterRawValueCallback(
std::unique_ptr<CallbackStore> PWMSim::RegisterPulseMicrosecondCallback(
NotifyCallback callback, bool initialNotify) {
auto store = std::make_unique<CallbackStore>(
m_index, -1, callback, &HALSIM_CancelPWMRawValueCallback);
store->SetUid(HALSIM_RegisterPWMRawValueCallback(m_index, &CallbackStoreThunk,
store.get(), initialNotify));
m_index, -1, callback, &HALSIM_CancelPWMPulseMicrosecondCallback);
store->SetUid(HALSIM_RegisterPWMPulseMicrosecondCallback(
m_index, &CallbackStoreThunk, store.get(), initialNotify));
return store;
}
int PWMSim::GetRawValue() const {
return HALSIM_GetPWMRawValue(m_index);
int32_t PWMSim::GetPulseMicrosecond() const {
return HALSIM_GetPWMPulseMicrosecond(m_index);
}
void PWMSim::SetRawValue(int rawValue) {
HALSIM_SetPWMRawValue(m_index, rawValue);
void PWMSim::SetPulseMicrosecond(int32_t microsecondPulseTime) {
HALSIM_SetPWMPulseMicrosecond(m_index, microsecondPulseTime);
}
std::unique_ptr<CallbackStore> PWMSim::RegisterSpeedCallback(

View File

@@ -7,6 +7,7 @@
#include <stdint.h>
#include <hal/Types.h>
#include <units/time.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>
@@ -18,18 +19,9 @@ class DMA;
* Class implements the PWM generation in the FPGA.
*
* The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
* are mapped to the hardware dependent values, in this case 0-2000 for the
* FPGA. Changes are immediately sent to the FPGA, and the update occurs at the
* next FPGA cycle (5.005ms). There is no delay.
*
* As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as
* follows:
* - 2000 = maximum pulse width
* - 1999 to 1001 = linear scaling from "full forward" to "center"
* - 1000 = center value
* - 999 to 2 = linear scaling from "center" to "full reverse"
* - 1 = minimum pulse width (currently 0.5ms)
* - 0 = disabled (i.e. PWM output is held low)
* are mapped to the microseconds to keep the pulse high, with a range of 0
* (off) to 4096. Changes are immediately sent to the FPGA, and the update
* occurs at the next FPGA cycle (5.05ms). There is no delay.
*/
class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
public:
@@ -40,15 +32,15 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
*/
enum PeriodMultiplier {
/**
* Don't skip pulses. PWM pulses occur every 5.005 ms
* Don't skip pulses. PWM pulses occur every 5.05 ms
*/
kPeriodMultiplier_1X = 1,
/**
* Skip every other pulse. PWM pulses occur every 10.010 ms
* Skip every other pulse. PWM pulses occur every 10.10 ms
*/
kPeriodMultiplier_2X = 2,
/**
* Skip three out of four pulses. PWM pulses occur every 20.020 ms
* Skip three out of four pulses. PWM pulses occur every 20.20 ms
*/
kPeriodMultiplier_4X = 4
};
@@ -78,30 +70,29 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
PWM& operator=(PWM&&) = default;
/**
* Set the PWM value directly to the hardware.
* Set the PWM pulse time directly to the hardware.
*
* Write a raw value to a PWM channel.
* Write a microsecond value to a PWM channel.
*
* @param value Raw PWM value.
* @param time Microsecond PWM value.
*/
virtual void SetRaw(uint16_t value);
virtual void SetPulseTime(units::microsecond_t time);
/**
* Get the PWM value directly from the hardware.
* Get the PWM pulse time directly from the hardware.
*
* Read a raw value from a PWM channel.
* Read a microsecond value from a PWM channel.
*
* @return Raw PWM control value.
* @return Microsecond PWM control value.
*/
virtual uint16_t GetRaw() const;
virtual units::microsecond_t GetPulseTime() const;
/**
* Set the PWM value based on a position.
*
* This is intended to be used by servos.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
* @pre SetBounds() called.
*
* @param pos The position to set the servo between 0.0 and 1.0.
*/
@@ -112,8 +103,7 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
*
* This is intended to be used by servos.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
* @pre SetBounds() called.
*
* @return The position the servo is set to between 0.0 and 1.0.
*/
@@ -124,11 +114,7 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
*
* This is intended to be used by motor controllers.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetCenterPwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
* @pre SetBounds() called.
*
* @param speed The speed to set the motor controller between -1.0 and 1.0.
*/
@@ -139,10 +125,7 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
*
* This is intended to be used by motor controllers.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
* @pre SetBounds() called.
*
* @return The most recently set speed between -1.0 and 1.0.
*/
@@ -180,46 +163,38 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper<PWM> {
* The values determine the upper and lower speeds as well as the deadband
* bracket.
*
* @param max The max PWM pulse width in ms
* @param deadbandMax The high end of the deadband range pulse width in ms
* @param center The center (off) pulse width in ms
* @param deadbandMin The low end of the deadband pulse width in ms
* @param min The minimum pulse width in ms
* @param max The max PWM pulse width in us
* @param deadbandMax The high end of the deadband range pulse width in us
* @param center The center (off) pulse width in us
* @param deadbandMin The low end of the deadband pulse width in us
* @param min The minimum pulse width in us
*/
void SetBounds(double max, double deadbandMax, double center,
double deadbandMin, double min);
/**
* Set the bounds on the PWM values.
*
* This sets the bounds on the PWM values for a particular each type of
* controller. The values determine the upper and lower speeds as well as the
* deadband bracket.
*
* @param max The Minimum pwm value
* @param deadbandMax The high end of the deadband range
* @param center The center speed (off)
* @param deadbandMin The low end of the deadband range
* @param min The minimum pwm value
*/
void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
int min);
void SetBounds(units::microsecond_t max, units::microsecond_t deadbandMax,
units::microsecond_t center, units::microsecond_t deadbandMin,
units::microsecond_t min);
/**
* Get the bounds on the PWM values.
*
* This Gets the bounds on the PWM values for a particular each type of
* This gets the bounds on the PWM values for a particular each type of
* controller. The values determine the upper and lower speeds as well as the
* deadband bracket.
*
* @param max The Minimum pwm value
* @param max The maximum pwm value
* @param deadbandMax The high end of the deadband range
* @param center The center speed (off)
* @param deadbandMin The low end of the deadband range
* @param min The minimum pwm value
*/
void GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center,
int32_t* deadbandMin, int32_t* min);
void GetBounds(units::microsecond_t* max, units::microsecond_t* deadbandMax,
units::microsecond_t* center,
units::microsecond_t* deadbandMin, units::microsecond_t* min);
/**
* Sets the PWM output to be a continuous high signal while enabled.
*
*/
void SetAlwaysHighMode();
int GetChannel() const;

View File

@@ -4,6 +4,8 @@
#pragma once
#include <units/angle.h>
#include "frc/PWM.h"
namespace frc {
@@ -98,11 +100,11 @@ class Servo : public PWM {
private:
double GetServoAngleRange() const;
static constexpr double kMaxServoAngle = 180.0;
static constexpr double kMaxServoAngle = 180.;
static constexpr double kMinServoAngle = 0.0;
static constexpr double kDefaultMaxServoPWM = 2.4;
static constexpr double kDefaultMinServoPWM = 0.6;
static constexpr units::millisecond_t kDefaultMaxServoPWM = 2.4_ms;
static constexpr units::millisecond_t kDefaultMinServoPWM = 0.6_ms;
};
} // namespace frc

View File

@@ -67,29 +67,29 @@ class PWMSim {
void SetInitialized(bool initialized);
/**
* Register a callback to be run when the PWM raw value changes.
* Register a callback to be run when the PWM pulse microsecond value changes.
*
* @param callback the callback
* @param initialNotify whether to run the callback with the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]]
std::unique_ptr<CallbackStore> RegisterRawValueCallback(
std::unique_ptr<CallbackStore> RegisterPulseMicrosecondCallback(
NotifyCallback callback, bool initialNotify);
/**
* Get the PWM raw value.
* Get the PWM pulse microsecond value.
*
* @return the PWM raw value
* @return the PWM pulse microsecond value
*/
int GetRawValue() const;
int32_t GetPulseMicrosecond() const;
/**
* Set the PWM raw value.
* Set the PWM pulse microsecond value.
*
* @param rawValue the PWM raw value
* @param microsecondPulseTime the PWM pulse microsecond value
*/
void SetRawValue(int rawValue);
void SetPulseMicrosecond(int32_t microsecondPulseTime);
/**
* Register a callback to be run when the PWM speed changes.

View File

@@ -26,7 +26,7 @@ TEST(PWMSimTest, Initialize) {
EXPECT_TRUE(sim.GetInitialized());
}
TEST(PWMSimTest, SetRawValue) {
TEST(PWMSimTest, SetPulseTime) {
HAL_Initialize(500, 0);
PWMSim sim{0};
@@ -35,13 +35,13 @@ TEST(PWMSimTest, SetRawValue) {
IntCallback callback;
auto cb = sim.RegisterRawValueCallback(callback.GetCallback(), false);
auto cb = sim.RegisterPulseMicrosecondCallback(callback.GetCallback(), false);
PWM pwm{0};
sim.SetRawValue(229);
EXPECT_EQ(229, sim.GetRawValue());
EXPECT_EQ(229, pwm.GetRaw());
sim.SetPulseMicrosecond(2290);
EXPECT_EQ(2290, sim.GetPulseMicrosecond());
EXPECT_EQ(2290, std::lround(pwm.GetPulseTime().value()));
EXPECT_TRUE(callback.WasTriggered());
EXPECT_EQ(229, callback.GetLastValue());
EXPECT_EQ(2290, callback.GetLastValue());
}
TEST(PWMSimTest, SetSpeed) {

View File

@@ -72,7 +72,7 @@ int main(void) {
}
// Set PWM config to standard servo speeds
HAL_SetPWMConfig(pwmPort, 2.0, 1.501, 1.5, 1.499, 1.0, &status);
HAL_SetPWMConfigMicroseconds(pwmPort, 2000, 1501, 1500, 1499, 1000, &status);
// Create an Input
status = 0;

View File

@@ -16,22 +16,17 @@ import edu.wpi.first.util.sendable.SendableRegistry;
* Class implements the PWM generation in the FPGA.
*
* <p>The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped to
* the hardware dependent values, in this case 0-2000 for the FPGA. Changes are immediately sent to
* the FPGA, and the update occurs at the next FPGA cycle (5.005ms). There is no delay.
*
* <p>As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as follows: - 2000 =
* maximum pulse width - 1999 to 1001 = linear scaling from "full forward" to "center" - 1000 =
* center value - 999 to 2 = linear scaling from "center" to "full reverse" - 1 = minimum pulse
* width (currently .5ms) - 0 = disabled (i.e. PWM output is held low)
* the microseconds to keep the pulse high, with a range of 0 (off) to 4096. Changes are immediately
* sent to the FPGA, and the update occurs at the next FPGA cycle (5.05ms). There is no delay.
*/
public class PWM implements Sendable, AutoCloseable {
/** Represents the amount to multiply the minimum servo-pulse pwm period by. */
public enum PeriodMultiplier {
/** Period Multiplier: don't skip pulses. PWM pulses occur every 5.005 ms */
/** Period Multiplier: don't skip pulses. PWM pulses occur every 5.05 ms */
k1X,
/** Period Multiplier: skip every other pulse. PWM pulses occur every 10.010 ms */
/** Period Multiplier: skip every other pulse. PWM pulses occur every 10.10 ms */
k2X,
/** Period Multiplier: skip three out of four pulses. PWM pulses occur every 20.020 ms */
/** Period Multiplier: skip three out of four pulses. PWM pulses occur every 20.20 ms */
k4X
}
@@ -103,15 +98,15 @@ public class PWM implements Sendable, AutoCloseable {
* type of controller. The values determine the upper and lower speeds as well as the deadband
* bracket.
*
* @param max The max PWM pulse width in ms
* @param deadbandMax The high end of the deadband range pulse width in ms
* @param center The center (off) pulse width in ms
* @param deadbandMin The low end of the deadband pulse width in ms
* @param min The minimum pulse width in ms
* @param max The max PWM pulse width in us
* @param deadbandMax The high end of the deadband range pulse width in us
* @param center The center (off) pulse width in us
* @param deadbandMin The low end of the deadband pulse width in us
* @param min The minimum pulse width in us
*/
public void setBounds(
double max, double deadbandMax, double center, double deadbandMin, double min) {
PWMJNI.setPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min);
public void setBoundsMicroseconds(
int max, int deadbandMax, int center, int deadbandMin, int min) {
PWMJNI.setPWMConfigMicroseconds(m_handle, max, deadbandMax, center, deadbandMin, min);
}
/**
@@ -121,8 +116,8 @@ public class PWM implements Sendable, AutoCloseable {
*
* @return The bounds on the PWM pulse widths.
*/
public PWMConfigDataResult getRawBounds() {
return PWMJNI.getPWMConfigRaw(m_handle);
public PWMConfigDataResult getBoundsMicroseconds() {
return PWMJNI.getPWMConfigMicroseconds(m_handle);
}
/**
@@ -140,8 +135,7 @@ public class PWM implements Sendable, AutoCloseable {
* <p>This is intended to be used by servos.
*
* @param pos The position to set the servo between 0.0 and 1.0.
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
* @pre setBoundsMicroseconds() called.
*/
public void setPosition(double pos) {
PWMJNI.setPWMPosition(m_handle, pos);
@@ -153,8 +147,7 @@ public class PWM implements Sendable, AutoCloseable {
* <p>This is intended to be used by servos.
*
* @return The position the servo is set to between 0.0 and 1.0.
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
* @pre setBoundsMicroseconds() called.
*/
public double getPosition() {
return PWMJNI.getPWMPosition(m_handle);
@@ -166,11 +159,7 @@ public class PWM implements Sendable, AutoCloseable {
* <p>This is intended to be used by motor controllers.
*
* @param speed The speed to set the motor controller between -1.0 and 1.0.
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetCenterPwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
* @pre setBoundsMicroseconds() called.
*/
public void setSpeed(double speed) {
PWMJNI.setPWMSpeed(m_handle, speed);
@@ -182,10 +171,7 @@ public class PWM implements Sendable, AutoCloseable {
* <p>This is intended to be used by motor controllers.
*
* @return The most recently set speed between -1.0 and 1.0.
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
* @pre setBoundsMicroseconds() called.
*/
public double getSpeed() {
return PWMJNI.getPWMSpeed(m_handle);
@@ -194,12 +180,12 @@ public class PWM implements Sendable, AutoCloseable {
/**
* Set the PWM value directly to the hardware.
*
* <p>Write a raw value to a PWM channel.
* <p>Write a microsecond pulse value to a PWM channel.
*
* @param value Raw PWM value. Range 0 - 255.
* @param microsecondPulseTime Microsecond pulse PWM value. Range 0 - 4096.
*/
public void setRaw(int value) {
PWMJNI.setPWMRaw(m_handle, (short) value);
public void setPulseTimeMicroseconds(int microsecondPulseTime) {
PWMJNI.setPulseTimeMicroseconds(m_handle, microsecondPulseTime);
}
/**
@@ -207,10 +193,10 @@ public class PWM implements Sendable, AutoCloseable {
*
* <p>Read a raw value from a PWM channel.
*
* @return Raw PWM control value. Range: 0 - 255.
* @return Microsecond pulse PWM control value. Range: 0 - 4096.
*/
public int getRaw() {
return PWMJNI.getPWMRaw(m_handle);
public int getPulseTimeMicroseconds() {
return PWMJNI.getPulseTimeMicroseconds(m_handle);
}
/** Temporarily disables the PWM output. The next set call will re-enable the output. */
@@ -246,6 +232,11 @@ public class PWM implements Sendable, AutoCloseable {
PWMJNI.latchPWMZero(m_handle);
}
/** Sets the PWM output to be a continous high signal while enabled. */
public void setAlwaysHighMode() {
PWMJNI.setAlwaysHighMode(m_handle);
}
/**
* Get the underlying handle.
*
@@ -260,6 +251,7 @@ public class PWM implements Sendable, AutoCloseable {
builder.setSmartDashboardType("PWM");
builder.setActuator(true);
builder.setSafeState(this::setDisabled);
builder.addDoubleProperty("Value", this::getRaw, value -> setRaw((int) value));
builder.addDoubleProperty(
"Value", this::getPulseTimeMicroseconds, value -> setPulseTimeMicroseconds((int) value));
}
}

View File

@@ -19,8 +19,8 @@ public class Servo extends PWM {
private static final double kMaxServoAngle = 180.0;
private static final double kMinServoAngle = 0.0;
protected static final double kDefaultMaxServoPWM = 2.4;
protected static final double kDefaultMinServoPWM = 0.6;
protected static final int kDefaultMaxServoPWM = 2400;
protected static final int kDefaultMinServoPWM = 600;
/**
* Constructor.<br>
@@ -33,7 +33,7 @@ public class Servo extends PWM {
*/
public Servo(final int channel) {
super(channel);
setBounds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
setBoundsMicroseconds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
setPeriodMultiplier(PeriodMultiplier.k4X);
HAL.report(tResourceType.kResourceType_Servo, getChannel() + 1);

View File

@@ -35,7 +35,7 @@ public class DMC60 extends PWMMotorController {
public DMC60(final int channel) {
super("DMC60", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -34,7 +34,7 @@ public class Jaguar extends PWMMotorController {
public Jaguar(final int channel) {
super("Jaguar", channel);
m_pwm.setBounds(2.31, 1.55, 1.507, 1.454, 0.697);
m_pwm.setBoundsMicroseconds(2310, 1550, 1507, 1454, 697);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -67,7 +67,7 @@ public class NidecBrushless extends MotorSafety
if (!m_disabled) {
m_speed = speed;
m_dio.updateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
m_pwm.setRaw(0xffff);
m_pwm.setAlwaysHighMode();
}
feed();

View File

@@ -34,7 +34,7 @@ public class PWMSparkMax extends PWMMotorController {
public PWMSparkMax(final int channel) {
super("PWMSparkMax", channel);
m_pwm.setBounds(2.003, 1.55, 1.50, 1.46, 0.999);
m_pwm.setBoundsMicroseconds(2003, 1550, 1500, 1460, 999);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class PWMTalonFX extends PWMMotorController {
public PWMTalonFX(final int channel) {
super("PWMTalonFX", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class PWMTalonSRX extends PWMMotorController {
public PWMTalonSRX(final int channel) {
super("PWMTalonSRX", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -34,7 +34,7 @@ public class PWMVenom extends PWMMotorController {
public PWMVenom(final int channel) {
super("PWMVenom", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class PWMVictorSPX extends PWMMotorController {
public PWMVictorSPX(final int channel) {
super("PWMVictorSPX", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class SD540 extends PWMMotorController {
public SD540(final int channel) {
super("SD540", channel);
m_pwm.setBounds(2.05, 1.55, 1.50, 1.44, 0.94);
m_pwm.setBoundsMicroseconds(2050, 1550, 1500, 1440, 940);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class Spark extends PWMMotorController {
public Spark(final int channel) {
super("Spark", channel);
m_pwm.setBounds(2.003, 1.55, 1.50, 1.46, 0.999);
m_pwm.setBoundsMicroseconds(2003, 1550, 1500, 1460, 999);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -34,7 +34,7 @@ public class Talon extends PWMMotorController {
public Talon(final int channel) {
super("Talon", channel);
m_pwm.setBounds(2.037, 1.539, 1.513, 1.487, 0.989);
m_pwm.setBoundsMicroseconds(2037, 1539, 1513, 1487, 989);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -37,7 +37,7 @@ public class Victor extends PWMMotorController {
public Victor(final int channel) {
super("Victor", channel);
m_pwm.setBounds(2.027, 1.525, 1.507, 1.49, 1.026);
m_pwm.setBoundsMicroseconds(2027, 1525, 1507, 1490, 1026);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k2X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -35,7 +35,7 @@ public class VictorSP extends PWMMotorController {
public VictorSP(final int channel) {
super("VictorSP", channel);
m_pwm.setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
m_pwm.setSpeed(0.0);
m_pwm.setZeroLatch();

View File

@@ -79,27 +79,28 @@ public class PWMSim {
* @return the {@link CallbackStore} object associated with this callback. Save a reference to
* this object so GC doesn't cancel the callback.
*/
public CallbackStore registerRawValueCallback(NotifyCallback callback, boolean initialNotify) {
int uid = PWMDataJNI.registerRawValueCallback(m_index, callback, initialNotify);
return new CallbackStore(m_index, uid, PWMDataJNI::cancelRawValueCallback);
public CallbackStore registerPulseMicrosecondCallback(
NotifyCallback callback, boolean initialNotify) {
int uid = PWMDataJNI.registerPulseMicrosecondCallback(m_index, callback, initialNotify);
return new CallbackStore(m_index, uid, PWMDataJNI::cancelPulseMicrosecondCallback);
}
/**
* Get the PWM raw value.
* Get the PWM pulse microsecond value.
*
* @return the PWM raw value
* @return the PWM pulse microsecond value
*/
public int getRawValue() {
return PWMDataJNI.getRawValue(m_index);
public int getPulseMicrosecond() {
return PWMDataJNI.getPulseMicrosecond(m_index);
}
/**
* Set the PWM raw value.
* Set the PWM pulse microsecond value.
*
* @param rawValue the PWM raw value
* @param microsecondPulseTime the PWM pulse microsecond value
*/
public void setRawValue(int rawValue) {
PWMDataJNI.setRawValue(m_index, rawValue);
public void setPulseMicrosecond(int microsecondPulseTime) {
PWMDataJNI.setPulseMicrosecond(m_index, microsecondPulseTime);
}
/**

View File

@@ -33,7 +33,7 @@ class PWMSimTest {
}
@Test
void testSetRawValue() {
void testSetPulseTime() {
HAL.initialize(500, 0);
PWMSim sim = new PWMSim(0);
@@ -42,13 +42,13 @@ class PWMSimTest {
IntCallback callback = new IntCallback();
try (CallbackStore cb = sim.registerRawValueCallback(callback, false);
try (CallbackStore cb = sim.registerPulseMicrosecondCallback(callback, false);
PWM pwm = new PWM(0)) {
sim.setRawValue(229);
assertEquals(229, sim.getRawValue());
assertEquals(229, pwm.getRaw());
sim.setPulseMicrosecond(2290);
assertEquals(2290, sim.getPulseMicrosecond());
assertEquals(2290, pwm.getPulseTimeMicroseconds());
assertTrue(callback.wasTriggered());
assertEquals(229, callback.getSetValue());
assertEquals(2290, callback.getSetValue());
}
}