mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
New 2018 and later build setup (#1001)
This commit is contained in:
committed by
Peter Johnson
parent
cb2c9eb6d5
commit
7f88cf768d
31
hal/src/main/native/cpp/cpp/fpga_clock.cpp
Normal file
31
hal/src/main/native/cpp/cpp/fpga_clock.cpp
Normal file
@@ -0,0 +1,31 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/cpp/fpga_clock.h"
|
||||
|
||||
#include <llvm/raw_ostream.h>
|
||||
|
||||
#include "HAL/HAL.h"
|
||||
|
||||
namespace hal {
|
||||
const fpga_clock::time_point fpga_clock::min_time =
|
||||
fpga_clock::time_point(fpga_clock::duration(
|
||||
std::numeric_limits<fpga_clock::duration::rep>::min()));
|
||||
|
||||
fpga_clock::time_point fpga_clock::now() noexcept {
|
||||
int32_t status = 0;
|
||||
uint64_t currentTime = HAL_GetFPGATime(&status);
|
||||
if (status != 0) {
|
||||
llvm::errs()
|
||||
<< "Call to HAL_GetFPGATime failed."
|
||||
<< "Initialization might have failed. Time will not be correct\n";
|
||||
llvm::errs().flush();
|
||||
return epoch();
|
||||
}
|
||||
return time_point(std::chrono::microseconds(currentTime));
|
||||
}
|
||||
} // namespace hal
|
||||
95
hal/src/main/native/cpp/handles/HandlesInternal.cpp
Normal file
95
hal/src/main/native/cpp/handles/HandlesInternal.cpp
Normal file
@@ -0,0 +1,95 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include <llvm/SmallVector.h>
|
||||
#include <support/mutex.h>
|
||||
|
||||
namespace hal {
|
||||
static llvm::SmallVector<HandleBase*, 32>* globalHandles = nullptr;
|
||||
static wpi::mutex globalHandleMutex;
|
||||
HandleBase::HandleBase() {
|
||||
static llvm::SmallVector<HandleBase*, 32> gH;
|
||||
std::lock_guard<wpi::mutex> lock(globalHandleMutex);
|
||||
if (!globalHandles) {
|
||||
globalHandles = &gH;
|
||||
}
|
||||
|
||||
auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
|
||||
if (index == globalHandles->end()) {
|
||||
globalHandles->push_back(this);
|
||||
} else {
|
||||
*index = this;
|
||||
}
|
||||
}
|
||||
HandleBase::~HandleBase() {
|
||||
std::lock_guard<wpi::mutex> lock(globalHandleMutex);
|
||||
auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
|
||||
if (index != globalHandles->end()) {
|
||||
*index = nullptr;
|
||||
}
|
||||
}
|
||||
void HandleBase::ResetHandles() {
|
||||
m_version++;
|
||||
if (m_version > 255) {
|
||||
m_version = 0;
|
||||
}
|
||||
}
|
||||
void HandleBase::ResetGlobalHandles() {
|
||||
std::unique_lock<wpi::mutex> lock(globalHandleMutex);
|
||||
for (auto&& i : *globalHandles) {
|
||||
if (i != nullptr) {
|
||||
lock.unlock();
|
||||
i->ResetHandles();
|
||||
lock.lock();
|
||||
}
|
||||
}
|
||||
}
|
||||
HAL_PortHandle createPortHandle(uint8_t channel, uint8_t module) {
|
||||
// set last 8 bits, then shift to first 8 bits
|
||||
HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
|
||||
handle = handle << 24;
|
||||
// shift module and add to 3rd set of 8 bits
|
||||
int32_t temp = module;
|
||||
temp = (temp << 8) & 0xff00;
|
||||
handle += temp;
|
||||
// add channel to last 8 bits
|
||||
handle += channel;
|
||||
return handle;
|
||||
}
|
||||
HAL_PortHandle createPortHandleForSPI(uint8_t channel) {
|
||||
// set last 8 bits, then shift to first 8 bits
|
||||
HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
|
||||
handle = handle << 16;
|
||||
// set second set up bits to 1
|
||||
int32_t temp = 1;
|
||||
temp = (temp << 8) & 0xff00;
|
||||
handle += temp;
|
||||
// shift to last set of bits
|
||||
handle = handle << 8;
|
||||
// add channel to last 8 bits
|
||||
handle += channel;
|
||||
return handle;
|
||||
}
|
||||
HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType,
|
||||
int16_t version) {
|
||||
if (index < 0) return HAL_kInvalidHandle;
|
||||
uint8_t hType = static_cast<uint8_t>(handleType);
|
||||
if (hType == 0 || hType > 127) return HAL_kInvalidHandle;
|
||||
// set last 8 bits, then shift to first 8 bits
|
||||
HAL_Handle handle = hType;
|
||||
handle = handle << 8;
|
||||
handle += static_cast<uint8_t>(version);
|
||||
handle = handle << 16;
|
||||
// add index to set last 16 bits
|
||||
handle += index;
|
||||
return handle;
|
||||
}
|
||||
} // namespace hal
|
||||
69
hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
Normal file
69
hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
Normal file
@@ -0,0 +1,69 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/Accelerometer.h"
|
||||
#include <jni.h>
|
||||
#include "edu_wpi_first_wpilibj_hal_AccelerometerJNI.h"
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AccelerometerJNI
|
||||
* Method: setAccelerometerActive
|
||||
* Signature: (Z)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AccelerometerJNI_setAccelerometerActive(
|
||||
JNIEnv *, jclass, jboolean active) {
|
||||
HAL_SetAccelerometerActive(active);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AccelerometerJNI
|
||||
* Method: setAccelerometerRange
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AccelerometerJNI_setAccelerometerRange(
|
||||
JNIEnv *, jclass, jint range) {
|
||||
HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AccelerometerJNI
|
||||
* Method: getAccelerometerX
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AccelerometerJNI_getAccelerometerX(
|
||||
JNIEnv *, jclass) {
|
||||
return HAL_GetAccelerometerX();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AccelerometerJNI
|
||||
* Method: getAccelerometerY
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AccelerometerJNI_getAccelerometerY(
|
||||
JNIEnv *, jclass) {
|
||||
return HAL_GetAccelerometerY();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AccelerometerJNI
|
||||
* Method: getAccelerometerZ
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AccelerometerJNI_getAccelerometerZ(
|
||||
JNIEnv *, jclass) {
|
||||
return HAL_GetAccelerometerZ();
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
219
hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
Normal file
219
hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
Normal file
@@ -0,0 +1,219 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_AnalogGyroJNI.h"
|
||||
|
||||
#include "HAL/AnalogGyro.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel analogGyroJNILogLevel = logWARNING;
|
||||
|
||||
#define ANALOGGYROJNI_LOG(level) \
|
||||
if (level > analogGyroJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: initializeAnalogGyro
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_initializeAnalogGyro(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI initializeAnalogGyro";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Analog Input Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_GyroHandle handle = HAL_InitializeAnalogGyro((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << handle;
|
||||
// Analog input does range checking, so we don't need to do so.
|
||||
CheckStatusForceThrow(env, status);
|
||||
return (jint) handle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: setupAnalogGyro
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setupAnalogGyro(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setupAnalogGyro";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetupAnalogGyro((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: freeAnalogGyro
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_freeAnalogGyro(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI freeAnalogGyro";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
HAL_FreeAnalogGyro((HAL_GyroHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: setAnalogGyroParameters
|
||||
* Signature: (IDDI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroParameters(
|
||||
JNIEnv* env, jclass, jint id, jdouble vPDPS, jdouble offset, jint center) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroParameters";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroParameters((HAL_GyroHandle)id, vPDPS, offset, center, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: setAnalogGyroVoltsPerDegreePerSecond
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroVoltsPerDegreePerSecond(
|
||||
JNIEnv* env, jclass, jint id, jdouble vPDPS) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroVoltsPerDegreePerSecond";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "vPDPS = " << vPDPS;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroVoltsPerDegreePerSecond((HAL_GyroHandle)id, vPDPS, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: resetAnalogGyro
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_resetAnalogGyro(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI resetAnalogGyro";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ResetAnalogGyro((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: calibrateAnalogGyro
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_calibrateAnalogGyro(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI calibrateAnalogGyro";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_CalibrateAnalogGyro((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: setAnalogGyroDeadband
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroDeadband(
|
||||
JNIEnv* env, jclass, jint id, jdouble deadband) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroDeadband";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroDeadband((HAL_GyroHandle)id, deadband, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: getAnalogGyroAngle
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroAngle(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroAngle";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble value = HAL_GetAnalogGyroAngle((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
|
||||
CheckStatus(env, status);
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: getAnalogGyroRate
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroRate(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroRate";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble value = HAL_GetAnalogGyroRate((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
|
||||
CheckStatus(env, status);
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: getAnalogGyroOffset
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroOffset(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroOffset";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble value = HAL_GetAnalogGyroOffset((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
|
||||
CheckStatus(env, status);
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI
|
||||
* Method: getAnalogGyroCenter
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroCenter(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroCenter";
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
|
||||
int32_t status = 0;
|
||||
jint value = HAL_GetAnalogGyroCenter((HAL_GyroHandle)id, &status);
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
|
||||
CheckStatus(env, status);
|
||||
return value;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
656
hal/src/main/native/cpp/jni/AnalogJNI.cpp
Normal file
656
hal/src/main/native/cpp/jni/AnalogJNI.cpp
Normal file
@@ -0,0 +1,656 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_AnalogJNI.h"
|
||||
|
||||
#include "HAL/AnalogInput.h"
|
||||
#include "HAL/AnalogOutput.h"
|
||||
#include "HAL/AnalogAccumulator.h"
|
||||
#include "HAL/AnalogTrigger.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel analogJNILogLevel = logWARNING;
|
||||
|
||||
#define ANALOGJNI_LOG(level) \
|
||||
if (level > analogJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: initializeAnalogInputPort
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_initializeAnalogInputPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
int32_t status = 0;
|
||||
auto analog = HAL_InitializeAnalogInputPort((HAL_PortHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << analog;
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumAnalogInputs(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jint)analog;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: freeAnalogInputPort
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_freeAnalogInputPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_AnalogInputHandle)id;
|
||||
HAL_FreeAnalogInputPort((HAL_AnalogInputHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: initializeAnalogOutputPort
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_initializeAnalogOutputPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_AnalogOutputHandle analog = HAL_InitializeAnalogOutputPort((HAL_PortHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << analog;
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumAnalogOutputs(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jlong)analog;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: freeAnalogOutputPort
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_freeAnalogOutputPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << id;
|
||||
HAL_FreeAnalogOutputPort((HAL_AnalogOutputHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: checkAnalogModule
|
||||
* Signature: (B)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_checkAnalogModule(
|
||||
JNIEnv *, jclass, jbyte value) {
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Module = " << (jint)value;
|
||||
jboolean returnValue = HAL_CheckAnalogModule(value);
|
||||
// ANALOGJNI_LOG(logDEBUG) << "checkAnalogModuleResult = " <<
|
||||
// (jint)returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: checkAnalogInputChannel
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_checkAnalogInputChannel(
|
||||
JNIEnv *, jclass, jint value) {
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Channel = " << value;
|
||||
jboolean returnValue = HAL_CheckAnalogInputChannel(value);
|
||||
// ANALOGJNI_LOG(logDEBUG) << "checkAnalogChannelResult = " <<
|
||||
// (jint)returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: checkAnalogOutputChannel
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_checkAnalogOutputChannel(
|
||||
JNIEnv *, jclass, jint value) {
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Channel = " << value;
|
||||
jboolean returnValue = HAL_CheckAnalogOutputChannel(value);
|
||||
// ANALOGJNI_LOG(logDEBUG) << "checkAnalogChannelResult = " <<
|
||||
// (jint)returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogOutput
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogOutput(
|
||||
JNIEnv *env, jclass, jint id, jdouble voltage) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Calling setAnalogOutput";
|
||||
ANALOGJNI_LOG(logDEBUG) << "Voltage = " << voltage;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogOutput((HAL_AnalogOutputHandle)id, voltage, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogOutput
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogOutput(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetAnalogOutput((HAL_AnalogOutputHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogSampleRate
|
||||
* Signature: (D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogSampleRate(
|
||||
JNIEnv *env, jclass, jdouble value) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "SampleRate = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogSampleRate(value, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogSampleRate
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogSampleRate(
|
||||
JNIEnv *env, jclass) {
|
||||
int32_t status = 0;
|
||||
double returnValue = HAL_GetAnalogSampleRate(&status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "SampleRate = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogAverageBits
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogAverageBits(
|
||||
JNIEnv *env, jclass, jint id, jint value) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "AverageBits = " << value;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogAverageBits((HAL_AnalogInputHandle)id, value, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogAverageBits
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogAverageBits(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetAnalogAverageBits((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AverageBits = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogOversampleBits
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogOversampleBits(
|
||||
JNIEnv *env, jclass, jint id, jint value) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "OversampleBits = " << value;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogOversampleBits((HAL_AnalogInputHandle)id, value, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogOversampleBits
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogOversampleBits(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetAnalogOversampleBits((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "OversampleBits = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogValue
|
||||
* Signature: (I)S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogValue(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (void*)id;
|
||||
int32_t status = 0;
|
||||
jshort returnValue = HAL_GetAnalogValue((HAL_AnalogInputHandle)id, &status);
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Value = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogAverageValue
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogAverageValue(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetAnalogAverageValue((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AverageValue = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogVoltsToValue
|
||||
* Signature: (ID)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogVoltsToValue(
|
||||
JNIEnv *env, jclass, jint id, jdouble voltageValue) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
ANALOGJNI_LOG(logDEBUG) << "VoltageValue = " << voltageValue;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetAnalogVoltsToValue((HAL_AnalogInputHandle)id, voltageValue, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Value = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogVoltage
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogVoltage(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (void*)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetAnalogVoltage((HAL_AnalogInputHandle)id, &status);
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
// ANALOGJNI_LOG(logDEBUG) << "Voltage = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogAverageVoltage
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogAverageVoltage(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetAnalogAverageVoltage((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AverageVoltage = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogLSBWeight
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogLSBWeight(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
|
||||
jint returnValue = HAL_GetAnalogLSBWeight((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AnalogLSBWeight = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogOffset
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogOffset(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
|
||||
jint returnValue = HAL_GetAnalogOffset((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AnalogOffset = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: isAccumulatorChannel
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_isAccumulatorChannel(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "isAccumulatorChannel";
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
|
||||
jboolean returnValue = HAL_IsAccumulatorChannel((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AnalogOffset = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: initAccumulator
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogJNI_initAccumulator(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_InitAccumulator((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: resetAccumulator
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_resetAccumulator(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ResetAccumulator((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAccumulatorCenter
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAccumulatorCenter(
|
||||
JNIEnv *env, jclass, jint id, jint center) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAccumulatorCenter((HAL_AnalogInputHandle)id, center, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAccumulatorDeadband
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAccumulatorDeadband(
|
||||
JNIEnv *env, jclass, jint id, jint deadband) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAccumulatorDeadband((HAL_AnalogInputHandle)id, deadband, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAccumulatorValue
|
||||
* Signature: (I)J
|
||||
*/
|
||||
JNIEXPORT jlong JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAccumulatorValue(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jlong returnValue = HAL_GetAccumulatorValue((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AccumulatorValue = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAccumulatorCount
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAccumulatorCount(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetAccumulatorCount((HAL_AnalogInputHandle)id, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AccumulatorCount = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAccumulatorOutput
|
||||
* Signature: (ILedu/wpi/first/wpilibj/AccumulatorResult;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAccumulatorOutput(
|
||||
JNIEnv *env, jclass, jint id, jobject accumulatorResult) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
|
||||
int32_t status = 0;
|
||||
int64_t value = 0;
|
||||
int64_t count = 0;
|
||||
HAL_GetAccumulatorOutput((HAL_AnalogInputHandle)id, &value, &count, &status);
|
||||
SetAccumulatorResultObject(env, accumulatorResult, value, count);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Count = " << count;
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: initializeAnalogTrigger
|
||||
* Signature: (ILjava/nio/IntBuffer;)J
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_initializeAnalogTrigger(
|
||||
JNIEnv *env, jclass, jint id, jobject index) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_AnalogInputHandle)id;
|
||||
jint *indexHandle = (jint *)env->GetDirectBufferAddress(index);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Index Ptr = " << indexHandle;
|
||||
int32_t status = 0;
|
||||
HAL_AnalogTriggerHandle analogTrigger =
|
||||
HAL_InitializeAnalogTrigger((HAL_AnalogInputHandle)id, (int32_t *)indexHandle, &status);
|
||||
ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ANALOGJNI_LOG(logDEBUG) << "AnalogTrigger Handle = " << analogTrigger;
|
||||
CheckStatus(env, status);
|
||||
return (jint)analogTrigger;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: cleanAnalogTrigger
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_cleanAnalogTrigger(
|
||||
JNIEnv *env, jclass,jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_CleanAnalogTrigger((HAL_AnalogTriggerHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogTriggerLimitsRaw
|
||||
* Signature: (III)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogTriggerLimitsRaw(
|
||||
JNIEnv *env, jclass,jint id, jint lower, jint upper) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogTriggerLimitsRaw((HAL_AnalogTriggerHandle)id, lower, upper, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogTriggerLimitsVoltage
|
||||
* Signature: (IDD)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogTriggerLimitsVoltage(
|
||||
JNIEnv *env, jclass,jint id, jdouble lower, jdouble upper) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogTriggerLimitsVoltage((HAL_AnalogTriggerHandle)id, lower, upper, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogTriggerAveraged
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogTriggerAveraged(
|
||||
JNIEnv *env, jclass,jint id, jboolean averaged) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogTriggerAveraged((HAL_AnalogTriggerHandle)id, averaged, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: setAnalogTriggerFiltered
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_setAnalogTriggerFiltered(
|
||||
JNIEnv *env, jclass,jint id, jboolean filtered) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogTriggerFiltered((HAL_AnalogTriggerHandle)id, filtered, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogTriggerInWindow
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogTriggerInWindow(
|
||||
JNIEnv *env, jclass,jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean val = HAL_GetAnalogTriggerInWindow((HAL_AnalogTriggerHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogTriggerTriggerState
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogTriggerTriggerState(
|
||||
JNIEnv *env, jclass,jint id) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean val = HAL_GetAnalogTriggerTriggerState((HAL_AnalogTriggerHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_AnalogJNI
|
||||
* Method: getAnalogTriggerOutput
|
||||
* Signature: (II)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_AnalogJNI_getAnalogTriggerOutput(
|
||||
JNIEnv *env, jclass,jint id, jint type) {
|
||||
ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = " << (HAL_AnalogTriggerHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean val =
|
||||
HAL_GetAnalogTriggerOutput((HAL_AnalogTriggerHandle)id, (HAL_AnalogTriggerType)type, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
153
hal/src/main/native/cpp/jni/CANJNI.cpp
Normal file
153
hal/src/main/native/cpp/jni/CANJNI.cpp
Normal file
@@ -0,0 +1,153 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
|
||||
#include "HAL/cpp/Log.h"
|
||||
#include "HAL/CAN.h"
|
||||
#include "HALUtil.h"
|
||||
#include "edu_wpi_first_wpilibj_can_CANJNI.h"
|
||||
#include "llvm/SmallString.h"
|
||||
#include "llvm/raw_ostream.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
// TLogLevel canJNILogLevel = logDEBUG;
|
||||
TLogLevel canJNILogLevel = logERROR;
|
||||
|
||||
#define CANJNI_LOG(level) \
|
||||
if (level > canJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_can_CANJNI
|
||||
* Method: FRCNetCommCANSessionMuxSendMessage
|
||||
* Signature: (I[BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxSendMessage(
|
||||
JNIEnv *env, jclass, jint messageID, jbyteArray data, jint periodMs) {
|
||||
|
||||
CANJNI_LOG(logDEBUG)
|
||||
<< "Calling CANJNI FRCNetCommCANSessionMuxSendMessage";
|
||||
|
||||
JByteArrayRef dataArray{env, data};
|
||||
|
||||
const uint8_t *dataBuffer = reinterpret_cast<const uint8_t*>(dataArray.array().data());
|
||||
uint8_t dataSize = dataArray.array().size();
|
||||
|
||||
CANJNI_LOG(logDEBUG) << "Message ID ";
|
||||
CANJNI_LOG(logDEBUG).write_hex(messageID);
|
||||
|
||||
if (logDEBUG <= canJNILogLevel) {
|
||||
if (dataBuffer) {
|
||||
llvm::SmallString<128> buf;
|
||||
llvm::raw_svector_ostream str(buf);
|
||||
for (int32_t i = 0; i < dataSize; i++) {
|
||||
str.write_hex(dataBuffer[i]) << ' ';
|
||||
}
|
||||
|
||||
Log().Get(logDEBUG) << "Data: " << str.str();
|
||||
} else {
|
||||
CANJNI_LOG(logDEBUG) << "Data: null";
|
||||
}
|
||||
}
|
||||
|
||||
CANJNI_LOG(logDEBUG) << "Period: " << periodMs;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_CAN_SendMessage(
|
||||
messageID, dataBuffer, dataSize, periodMs, &status);
|
||||
|
||||
CANJNI_LOG(logDEBUG) << "Status: " << status;
|
||||
CheckCANStatus(env, status, messageID);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_can_CANJNI
|
||||
* Method: FRCNetCommCANSessionMuxReceiveMessage
|
||||
* Signature: (Ljava/nio/IntBuffer;ILjava/nio/ByteBuffer;)[B
|
||||
*/
|
||||
JNIEXPORT jbyteArray JNICALL
|
||||
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage(
|
||||
JNIEnv *env, jclass, jobject messageID, jint messageIDMask,
|
||||
jobject timeStamp) {
|
||||
|
||||
CANJNI_LOG(logDEBUG)
|
||||
<< "Calling CANJNI FRCNetCommCANSessionMuxReceiveMessage";
|
||||
|
||||
uint32_t *messageIDPtr = (uint32_t *)env->GetDirectBufferAddress(messageID);
|
||||
uint32_t *timeStampPtr = (uint32_t *)env->GetDirectBufferAddress(timeStamp);
|
||||
|
||||
uint8_t dataSize = 0;
|
||||
uint8_t buffer[8];
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_CAN_ReceiveMessage(
|
||||
messageIDPtr, messageIDMask, buffer, &dataSize, timeStampPtr, &status);
|
||||
|
||||
CANJNI_LOG(logDEBUG) << "Message ID ";
|
||||
CANJNI_LOG(logDEBUG).write_hex(*messageIDPtr);
|
||||
|
||||
if (logDEBUG <= canJNILogLevel) {
|
||||
llvm::SmallString<128> buf;
|
||||
llvm::raw_svector_ostream str(buf);
|
||||
|
||||
for (int32_t i = 0; i < dataSize; i++) {
|
||||
// Pad one-digit data with a zero
|
||||
if (buffer[i] <= 16) {
|
||||
str << '0';
|
||||
}
|
||||
|
||||
str.write_hex(buffer[i]) << ' ';
|
||||
}
|
||||
|
||||
Log().Get(logDEBUG) << "Data: " << str.str();
|
||||
}
|
||||
|
||||
CANJNI_LOG(logDEBUG) << "Timestamp: " << *timeStampPtr;
|
||||
CANJNI_LOG(logDEBUG) << "Status: " << status;
|
||||
|
||||
if (!CheckCANStatus(env, status, *messageIDPtr)) return nullptr;
|
||||
return MakeJByteArray(env, llvm::StringRef{reinterpret_cast<const char*>(buffer),
|
||||
static_cast<size_t>(dataSize)});
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_can_CANJNI
|
||||
* Method: GetCANStatus
|
||||
* Signature: (Ledu/wpi/first/wpilibj/can/CANStatus;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_can_CANJNI_GetCANStatus
|
||||
(JNIEnv *env, jclass, jobject canStatus) {
|
||||
CANJNI_LOG(logDEBUG)
|
||||
<< "Calling CANJNI HAL_CAN_GetCANStatus";
|
||||
|
||||
float percentBusUtilization = 0;
|
||||
uint32_t busOffCount = 0;
|
||||
uint32_t txFullCount = 0;
|
||||
uint32_t receiveErrorCount = 0;
|
||||
uint32_t transmitErrorCount = 0;
|
||||
int32_t status = 0;
|
||||
HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
|
||||
&receiveErrorCount, &transmitErrorCount, &status);
|
||||
|
||||
if (!CheckStatus(env, status)) return;
|
||||
|
||||
SetCanStatusObject(env, canStatus, percentBusUtilization, busOffCount,
|
||||
txFullCount, receiveErrorCount, transmitErrorCount);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
211
hal/src/main/native/cpp/jni/CompressorJNI.cpp
Normal file
211
hal/src/main/native/cpp/jni/CompressorJNI.cpp
Normal file
@@ -0,0 +1,211 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/Compressor.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HAL/Solenoid.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/cpp/Log.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_CompressorJNI.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: initializeCompressor
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_initializeCompressor(
|
||||
JNIEnv *env, jclass, jbyte module) {
|
||||
int32_t status = 0;
|
||||
auto handle = HAL_InitializeCompressor(module, &status);
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumPCMModules(), module);
|
||||
|
||||
return (jint)handle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: checkCompressorModule
|
||||
* Signature: (B)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_checkCompressorModule(
|
||||
JNIEnv *env, jclass, jbyte module) {
|
||||
return HAL_CheckCompressorModule(module);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressor
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressor(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressor((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: setCompressorClosedLoopControl
|
||||
* Signature: (JZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_setCompressorClosedLoopControl(
|
||||
JNIEnv *env, jclass, jint compressorHandle, jboolean value) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCompressorClosedLoopControl((HAL_CompressorHandle)compressorHandle, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorClosedLoopControl
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorClosedLoopControl(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorClosedLoopControl((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorPressureSwitch
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorPressureSwitch(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorPressureSwitch((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorCurrent
|
||||
* Signature: (J)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorCurrent(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetCompressorCurrent((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorCurrentTooHighFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorCurrentTooHighFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorCurrentTooHighFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorCurrentTooHighStickyFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorCurrentTooHighStickyFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val =
|
||||
HAL_GetCompressorCurrentTooHighStickyFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorShortedStickyFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorShortedStickyFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorShortedStickyFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorShortedFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorShortedFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorShortedFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorNotConnectedStickyFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorNotConnectedStickyFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorNotConnectedStickyFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: getCompressorNotConnectedFault
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorNotConnectedFault(
|
||||
JNIEnv *env, jclass, jint compressorHandle) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetCompressorNotConnectedFault((HAL_CompressorHandle)compressorHandle, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CompressorJNI
|
||||
* Method: clearAllPCMStickyFaults
|
||||
* Signature: (J)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CompressorJNI_clearAllPCMStickyFaults(
|
||||
JNIEnv *env, jclass, jbyte module) {
|
||||
int32_t status = 0;
|
||||
HAL_ClearAllPCMStickyFaults((uint8_t)module, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
42
hal/src/main/native/cpp/jni/ConstantsJNI.cpp
Normal file
42
hal/src/main/native/cpp/jni/ConstantsJNI.cpp
Normal file
@@ -0,0 +1,42 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_ConstantsJNI.h"
|
||||
|
||||
#include "HAL/Constants.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel constantsJNILogLevel = logWARNING;
|
||||
|
||||
#define CONSTANTSJNI_LOG(level) \
|
||||
if (level > constantsJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_ConstantsJNI
|
||||
* Method: getSystemClockTicksPerMicrosecond
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_ConstantsJNI_getSystemClockTicksPerMicrosecond(
|
||||
JNIEnv *env, jclass) {
|
||||
CONSTANTSJNI_LOG(logDEBUG) << "Calling ConstantsJNI getSystemClockTicksPerMicrosecond";
|
||||
jint value = HAL_GetSystemClockTicksPerMicrosecond();
|
||||
CONSTANTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
}
|
||||
443
hal/src/main/native/cpp/jni/CounterJNI.cpp
Normal file
443
hal/src/main/native/cpp/jni/CounterJNI.cpp
Normal file
@@ -0,0 +1,443 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_CounterJNI.h"
|
||||
|
||||
#include "HAL/Counter.h"
|
||||
#include "HAL/Errors.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel counterJNILogLevel = logWARNING;
|
||||
|
||||
#define COUNTERJNI_LOG(level) \
|
||||
if (level > counterJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: initializeCounter
|
||||
* Signature: (ILjava/nio/IntBuffer;)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_initializeCounter(
|
||||
JNIEnv* env, jclass, jint mode, jobject index) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI initializeCounter";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Mode = " << mode;
|
||||
jint* indexPtr = (jint*)env->GetDirectBufferAddress(index);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Index Ptr = " << (int32_t*)indexPtr;
|
||||
int32_t status = 0;
|
||||
auto counter = HAL_InitializeCounter((HAL_Counter_Mode)mode, (int32_t*)indexPtr, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Index = " << *indexPtr;
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
COUNTERJNI_LOG(logDEBUG) << "COUNTER Handle = " << counter;
|
||||
CheckStatusForceThrow(env, status);
|
||||
return (jint)counter;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: freeCounter
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CounterJNI_freeCounter(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI freeCounter";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_FreeCounter((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterAverageSize
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterAverageSize(
|
||||
JNIEnv* env, jclass, jint id, jint value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterAverageSize";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "AverageSize = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterAverageSize((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterUpSource
|
||||
* Signature: (III)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterUpSource(
|
||||
JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
|
||||
jint analogTriggerType) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpSource";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
|
||||
COUNTERJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSource((HAL_CounterHandle)id, (HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterUpSourceEdge
|
||||
* Signature: (IZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterUpSourceEdge(
|
||||
JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpSourceEdge";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "Rise = " << (jint)valueRise;
|
||||
COUNTERJNI_LOG(logDEBUG) << "Fall = " << (jint)valueFall;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSourceEdge((HAL_CounterHandle)id, valueRise, valueFall, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: clearCounterUpSource
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_clearCounterUpSource(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI clearCounterUpSource";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterUpSource((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterDownSource
|
||||
* Signature: (IIZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterDownSource(
|
||||
JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
|
||||
jint analogTriggerType) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterDownSource";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
|
||||
COUNTERJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSource((HAL_CounterHandle)id, (HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
if (status == PARAMETER_OUT_OF_RANGE) {
|
||||
ThrowIllegalArgumentException(env,
|
||||
"Counter only supports DownSource in "
|
||||
"TwoPulse and ExternalDirection modes.");
|
||||
return;
|
||||
}
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterDownSourceEdge
|
||||
* Signature: (IZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterDownSourceEdge(
|
||||
JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterDownSourceEdge";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "Rise = " << (jint)valueRise;
|
||||
COUNTERJNI_LOG(logDEBUG) << "Fall = " << (jint)valueFall;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSourceEdge((HAL_CounterHandle)id, valueRise, valueFall, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: clearCounterDownSource
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_clearCounterDownSource(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI clearCounterDownSource";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterDownSource((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterUpDownMode
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterUpDownMode(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpDownMode";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpDownMode((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterExternalDirectionMode
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterExternalDirectionMode(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG)
|
||||
<< "Calling COUNTERJNI setCounterExternalDirectionMode";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterExternalDirectionMode((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterSemiPeriodMode
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterSemiPeriodMode(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterSemiPeriodMode";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "SemiPeriodMode = " << (jint)value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSemiPeriodMode((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterPulseLengthMode
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterPulseLengthMode(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterPulseLengthMode";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "PulseLengthMode = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterPulseLengthMode((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: getCounterSamplesToAverage
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_getCounterSamplesToAverage(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterSamplesToAverage";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetCounterSamplesToAverage((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
COUNTERJNI_LOG(logDEBUG) << "getCounterSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterSamplesToAverage
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterSamplesToAverage(
|
||||
JNIEnv* env, jclass, jint id, jint value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterSamplesToAverage";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "SamplesToAverage = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSamplesToAverage((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
if (status == PARAMETER_OUT_OF_RANGE) {
|
||||
ThrowBoundaryException(env, value, 1, 127);
|
||||
return;
|
||||
}
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: resetCounter
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CounterJNI_resetCounter(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI resetCounter";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ResetCounter((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: getCounter
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CounterJNI_getCounter(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
// COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounter";
|
||||
// COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetCounter((HAL_CounterHandle)id, &status);
|
||||
// COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
// COUNTERJNI_LOG(logDEBUG) << "getCounterResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: getCounterPeriod
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_getCounterPeriod(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterPeriod";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetCounterPeriod((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
COUNTERJNI_LOG(logDEBUG) << "getCounterPeriodResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterMaxPeriod
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterMaxPeriod(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterMaxPeriod";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "MaxPeriod = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterMaxPeriod((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterUpdateWhenEmpty
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterUpdateWhenEmpty(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterMaxPeriod";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "UpdateWhenEmpty = " << (jint)value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpdateWhenEmpty((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: getCounterStopped
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_getCounterStopped(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterStopped";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetCounterStopped((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
COUNTERJNI_LOG(logDEBUG) << "getCounterStoppedResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: getCounterDirection
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_getCounterDirection(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterDirection";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetCounterDirection((HAL_CounterHandle)id, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
COUNTERJNI_LOG(logDEBUG) << "getCounterDirectionResult = "
|
||||
<< (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_CounterJNI
|
||||
* Method: setCounterReverseDirection
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_CounterJNI_setCounterReverseDirection(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterReverseDirection";
|
||||
COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
|
||||
COUNTERJNI_LOG(logDEBUG) << "ReverseDirection = " << (jint)value;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterReverseDirection((HAL_CounterHandle)id, value, &status);
|
||||
COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
289
hal/src/main/native/cpp/jni/DIOJNI.cpp
Normal file
289
hal/src/main/native/cpp/jni/DIOJNI.cpp
Normal file
@@ -0,0 +1,289 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_DIOJNI.h"
|
||||
|
||||
#include "HAL/DIO.h"
|
||||
#include "HAL/PWM.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel dioJNILogLevel = logWARNING;
|
||||
|
||||
#define DIOJNI_LOG(level) \
|
||||
if (level > dioJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: initializeDIOPort
|
||||
* Signature: (IZ)I;
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_initializeDIOPort(
|
||||
JNIEnv *env, jclass, jint id, jboolean input) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI initializeDIOPort";
|
||||
DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
DIOJNI_LOG(logDEBUG) << "Input = " << (jint)input;
|
||||
int32_t status = 0;
|
||||
auto dio = HAL_InitializeDIOPort((HAL_PortHandle)id, (uint8_t)input, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "DIO Handle = " << dio;
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumDigitalChannels(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jint)dio;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: checkDIOChannel
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_checkDIOChannel(
|
||||
JNIEnv *env, jclass, jint channel) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI checkDIOChannel";
|
||||
DIOJNI_LOG(logDEBUG) << "Channel = " << channel;
|
||||
return HAL_CheckDIOChannel(channel);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: freeDIOPort
|
||||
* Signature: (I)V;
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_freeDIOPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI freeDIOPort";
|
||||
DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
HAL_FreeDIOPort((HAL_DigitalHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setDIO
|
||||
* Signature: (IS)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDIO(
|
||||
JNIEnv *env, jclass, jint id, jshort value) {
|
||||
// DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDIO";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
// DIOJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetDIO((HAL_DigitalHandle)id, value, &status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setDIODirection
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDIODirection(
|
||||
JNIEnv *env, jclass, jint id, jboolean input) {
|
||||
// DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDIO";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
// DIOJNI_LOG(logDEBUG) << "IsInput = " << input;
|
||||
int32_t status = 0;
|
||||
HAL_SetDIODirection((HAL_DigitalHandle)id, input, &status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: getDIO
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_getDIO(JNIEnv *env, jclass, jint id) {
|
||||
// DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getDIO";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetDIO((HAL_DigitalHandle)id, &status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
// DIOJNI_LOG(logDEBUG) << "getDIOResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: getDIODirection
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_getDIODirection(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getDIODirection (RR upd)";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetDIODirection((HAL_DigitalHandle)id, &status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "getDIODirectionResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: pulse
|
||||
* Signature: (JD)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_pulse(
|
||||
JNIEnv *env, jclass, jint id, jdouble value) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI pulse (RR upd)";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
// DIOJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_Pulse((HAL_DigitalHandle)id, value, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Did it work? Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: isPulsing
|
||||
* Signature: (J)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_isPulsing(JNIEnv *env, jclass, jint id) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI isPulsing (RR upd)";
|
||||
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_IsPulsing((HAL_DigitalHandle)id, &status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "isPulsingResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: isAnyPulsing
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_isAnyPulsing(JNIEnv *env, jclass) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI isAnyPulsing (RR upd)";
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_IsAnyPulsing(&status);
|
||||
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "isAnyPulsingResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: getLoopTiming
|
||||
* Signature: ()S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_getLoopTiming(JNIEnv *env, jclass) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getLoopTimeing";
|
||||
int32_t status = 0;
|
||||
jshort returnValue = HAL_GetPWMLoopTiming(&status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "LoopTiming = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: allocateDigitalPWM
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_allocateDigitalPWM(JNIEnv* env, jclass) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI allocateDigitalPWM";
|
||||
int32_t status = 0;
|
||||
auto pwm = HAL_AllocateDigitalPWM(&status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
DIOJNI_LOG(logDEBUG) << "PWM Handle = " << pwm;
|
||||
CheckStatus(env, status);
|
||||
return (jint)pwm;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: freeDigitalPWM
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_freeDigitalPWM(JNIEnv* env, jclass, jint id) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI freeDigitalPWM";
|
||||
DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_FreeDigitalPWM((HAL_DigitalPWMHandle)id, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setDigitalPWMRate
|
||||
* Signature: (D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDigitalPWMRate(
|
||||
JNIEnv* env, jclass, jdouble value) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMRate";
|
||||
DIOJNI_LOG(logDEBUG) << "Rate= " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetDigitalPWMRate(value, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setDigitalPWMDutyCycle
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDigitalPWMDutyCycle(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMDutyCycle";
|
||||
DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
|
||||
DIOJNI_LOG(logDEBUG) << "DutyCycle= " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetDigitalPWMDutyCycle((HAL_DigitalPWMHandle)id, value, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setDigitalPWMOutputChannel
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDigitalPWMOutputChannel(
|
||||
JNIEnv* env, jclass, jint id, jint value) {
|
||||
DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMOutputChannel";
|
||||
DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
|
||||
DIOJNI_LOG(logDEBUG) << "Channel= " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetDigitalPWMOutputChannel((HAL_DigitalPWMHandle)id, (uint32_t)value, &status);
|
||||
DIOJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
70
hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
Normal file
70
hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
Normal file
@@ -0,0 +1,70 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <jni.h>
|
||||
#include "HAL/DIO.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI
|
||||
* Method: setFilterSelect
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI_setFilterSelect(
|
||||
JNIEnv* env, jclass, jint id, jint filter_index) {
|
||||
int32_t status = 0;
|
||||
|
||||
HAL_SetFilterSelect(static_cast<HAL_DigitalHandle>(id), filter_index,
|
||||
&status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI
|
||||
* Method: getFilterSelect
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI_getFilterSelect(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
int32_t status = 0;
|
||||
|
||||
jint result =
|
||||
HAL_GetFilterSelect(static_cast<HAL_DigitalHandle>(id), &status);
|
||||
CheckStatus(env, status);
|
||||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI
|
||||
* Method: setFilterPeriod
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI_setFilterPeriod(
|
||||
JNIEnv* env, jclass, jint filter_index, jint fpga_cycles) {
|
||||
int32_t status = 0;
|
||||
|
||||
HAL_SetFilterPeriod(filter_index, fpga_cycles, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI
|
||||
* Method: getFilterPeriod
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_DigitalGlitchFilterJNI_getFilterPeriod(
|
||||
JNIEnv* env, jclass, jint filter_index) {
|
||||
int32_t status = 0;
|
||||
|
||||
jint result = HAL_GetFilterPeriod(filter_index, &status);
|
||||
CheckStatus(env, status);
|
||||
return result;
|
||||
}
|
||||
454
hal/src/main/native/cpp/jni/EncoderJNI.cpp
Normal file
454
hal/src/main/native/cpp/jni/EncoderJNI.cpp
Normal file
@@ -0,0 +1,454 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_EncoderJNI.h"
|
||||
|
||||
#include "HAL/Encoder.h"
|
||||
#include "HAL/Errors.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel encoderJNILogLevel = logWARNING;
|
||||
|
||||
#define ENCODERJNI_LOG(level) \
|
||||
if (level > encoderJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: initializeEncoder
|
||||
* Signature: (IIIIZI)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_initializeEncoder(
|
||||
JNIEnv* env, jclass, jint digitalSourceHandleA, jint analogTriggerTypeA,
|
||||
jint digitalSourceHandleB, jint analogTriggerTypeB, jboolean reverseDirection,
|
||||
jint encodingType) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI initializeEncoder";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Source Handle A = " << digitalSourceHandleA;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type A = "
|
||||
<< analogTriggerTypeA;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Source Handle B = " << digitalSourceHandleB;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type B = "
|
||||
<< analogTriggerTypeB;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Reverse direction = " << (jint)reverseDirection;
|
||||
ENCODERJNI_LOG(logDEBUG) << "EncodingType = " << encodingType;
|
||||
int32_t status = 0;
|
||||
auto encoder = HAL_InitializeEncoder(
|
||||
(HAL_Handle)digitalSourceHandleA, (HAL_AnalogTriggerType)analogTriggerTypeA,
|
||||
(HAL_Handle)digitalSourceHandleB, (HAL_AnalogTriggerType)analogTriggerTypeB,
|
||||
reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
|
||||
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "ENCODER Handle = " << encoder;
|
||||
CheckStatusForceThrow(env, status);
|
||||
return (jint)encoder;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: freeEncoder
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_EncoderJNI_freeEncoder(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI freeEncoder";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_FreeEncoder((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoder
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoder(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoder";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoder((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderRaw
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderRaw(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderRaw";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderRaw((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getRawEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncodingScaleFactor
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncodingScaleFactor(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncodingScaleFactor";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncodingScaleFactorResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: resetEncoder
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_EncoderJNI_resetEncoder(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI resetEncoder";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_ResetEncoder((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderPeriod
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderPeriod(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderPeriod";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
double returnValue = HAL_GetEncoderPeriod((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderPeriodEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderMaxPeriod
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderMaxPeriod(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderMaxPeriod";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderMaxPeriod((HAL_EncoderHandle)id, value, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderStopped
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderStopped(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderStopped";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetEncoderStopped((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getStoppedEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderDirection
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDirection(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderDirection";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetEncoderDirection((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getDirectionEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderDistance
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDistance(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderDistance";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetEncoderDistance((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getDistanceEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderRate
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderRate(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderRate";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetEncoderRate((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getRateEncoderResult = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderMinRate
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderMinRate(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderMinRate";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderMinRate((HAL_EncoderHandle)id, value, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderDistancePerPulse
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderDistancePerPulse(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderDistancePerPulse";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderDistancePerPulse((HAL_EncoderHandle)id, value, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderReverseDirection
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderReverseDirection(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderReverseDirection";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderReverseDirection((HAL_EncoderHandle)id, value, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderSamplesToAverage
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderSamplesToAverage(
|
||||
JNIEnv* env, jclass, jint id, jint value) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderSamplesToAverage((HAL_EncoderHandle)id, value, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
if (status == PARAMETER_OUT_OF_RANGE) {
|
||||
ThrowBoundaryException(env, value, 1, 127);
|
||||
return;
|
||||
}
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderSamplesToAverage
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderSamplesToAverage(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderSamplesToAverage((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: setEncoderIndexSource
|
||||
* Signature: (IIII)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderIndexSource(
|
||||
JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
|
||||
jint analogTriggerType, jint type) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderIndexSource";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Source Handle = " << digitalSourceHandle;
|
||||
ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type = "
|
||||
<< analogTriggerType;
|
||||
ENCODERJNI_LOG(logDEBUG) << "IndexingType = " << type;
|
||||
int32_t status = 0;
|
||||
HAL_SetEncoderIndexSource((HAL_EncoderHandle)id, (HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType,
|
||||
(HAL_EncoderIndexingType)type, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderFPGAIndex
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderFPGAIndex(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderFPGAIndex((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderEncodingScale
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderEncodingScale(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderDecodingScaleFactor
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDecodingScaleFactor(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetEncoderDecodingScaleFactor((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderDistancePerPulse
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDistancePerPulse(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetEncoderDistancePerPulse((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_EncoderJNI
|
||||
* Method: getEncoderEncodingType
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderEncodingType(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
|
||||
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetEncoderEncodingType((HAL_EncoderHandle)id, &status);
|
||||
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
|
||||
<< returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
433
hal/src/main/native/cpp/jni/HAL.cpp
Normal file
433
hal/src/main/native/cpp/jni/HAL.cpp
Normal file
@@ -0,0 +1,433 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <cstring>
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "HAL/HAL.h"
|
||||
#include "HAL/DriverStation.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_HAL.h"
|
||||
#include "HALUtil.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
static TLogLevel netCommLogLevel = logWARNING;
|
||||
|
||||
#define NETCOMM_LOG(level) \
|
||||
if (level > netCommLogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: Initialize
|
||||
* Signature: (Z)II
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_initialize(JNIEnv*, jclass, jint timeout, jint mode) {
|
||||
return HAL_Initialize(timeout, mode);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: observeUserProgramStarting
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramStarting(JNIEnv*, jclass) {
|
||||
HAL_ObserveUserProgramStarting();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: observeUserProgramDisabled
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramDisabled(JNIEnv*, jclass) {
|
||||
HAL_ObserveUserProgramDisabled();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: observeUserProgramAutonomous
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramAutonomous(
|
||||
JNIEnv*, jclass) {
|
||||
HAL_ObserveUserProgramAutonomous();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: observeUserProgramTeleop
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramTeleop(JNIEnv*, jclass) {
|
||||
HAL_ObserveUserProgramTeleop();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: observeUserProgramTest
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramTest(JNIEnv*, jclass) {
|
||||
HAL_ObserveUserProgramTest();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_Report
|
||||
* Signature: (IIILjava/lang/String;)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_report(
|
||||
JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
|
||||
jint paramContext, jstring paramFeature) {
|
||||
JStringRef featureStr{paramEnv, paramFeature};
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL report "
|
||||
<< "res:" << paramResource
|
||||
<< " instance:" << paramInstanceNumber
|
||||
<< " context:" << paramContext
|
||||
<< " feature:" << featureStr.c_str();
|
||||
jint returnValue =
|
||||
HAL_Report(paramResource, paramInstanceNumber, paramContext, featureStr.c_str());
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: NativeGetControlWord
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_nativeGetControlWord(JNIEnv*, jclass) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL Control Word";
|
||||
static_assert(sizeof(HAL_ControlWord) == sizeof(jint),
|
||||
"Java int must match the size of control word");
|
||||
HAL_ControlWord controlWord;
|
||||
std::memset(&controlWord, 0, sizeof(HAL_ControlWord));
|
||||
HAL_GetControlWord(&controlWord);
|
||||
jint retVal = 0;
|
||||
std::memcpy(&retVal, &controlWord, sizeof(HAL_ControlWord));
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: NativeGetAllianceStation
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_nativeGetAllianceStation(JNIEnv*, jclass) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL Alliance Station";
|
||||
int32_t status = 0;
|
||||
auto allianceStation = HAL_GetAllianceStation(&status);
|
||||
return static_cast<jint>(allianceStation);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickAxes
|
||||
* Signature: (B[F)S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickAxes(JNIEnv* env, jclass,
|
||||
jbyte joystickNum,
|
||||
jfloatArray axesArray) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickAxes";
|
||||
HAL_JoystickAxes axes;
|
||||
HAL_GetJoystickAxes(joystickNum, &axes);
|
||||
|
||||
jsize javaSize = env->GetArrayLength(axesArray);
|
||||
if (axes.count > javaSize)
|
||||
{
|
||||
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
|
||||
}
|
||||
|
||||
env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
|
||||
|
||||
return axes.count;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickPOVs
|
||||
* Signature: (B[S)S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickPOVs(JNIEnv* env, jclass,
|
||||
jbyte joystickNum,
|
||||
jshortArray povsArray) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickPOVs";
|
||||
HAL_JoystickPOVs povs;
|
||||
HAL_GetJoystickPOVs(joystickNum, &povs);
|
||||
|
||||
jsize javaSize = env->GetArrayLength(povsArray);
|
||||
if (povs.count > javaSize)
|
||||
{
|
||||
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
|
||||
}
|
||||
|
||||
env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
|
||||
|
||||
return povs.count;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickButtons
|
||||
* Signature: (BL)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickButtons(JNIEnv* env, jclass,
|
||||
jbyte joystickNum,
|
||||
jobject count) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickButtons";
|
||||
HAL_JoystickButtons joystickButtons;
|
||||
HAL_GetJoystickButtons(joystickNum, &joystickButtons);
|
||||
jbyte *countPtr = (jbyte *)env->GetDirectBufferAddress(count);
|
||||
NETCOMM_LOG(logDEBUG) << "Buttons = " << joystickButtons.buttons;
|
||||
NETCOMM_LOG(logDEBUG) << "Count = " << (jint)joystickButtons.count;
|
||||
*countPtr = joystickButtons.count;
|
||||
NETCOMM_LOG(logDEBUG) << "CountBuffer = " << (jint)*countPtr;
|
||||
return joystickButtons.buttons;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_SetJoystickOutputs
|
||||
* Signature: (BISS)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_setJoystickOutputs(JNIEnv*, jclass,
|
||||
jbyte port, jint outputs,
|
||||
jshort leftRumble,
|
||||
jshort rightRumble) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL_SetJoystickOutputs on port " << port;
|
||||
NETCOMM_LOG(logDEBUG) << "Outputs: " << outputs;
|
||||
NETCOMM_LOG(logDEBUG) << "Left Rumble: " << leftRumble
|
||||
<< " Right Rumble: " << rightRumble;
|
||||
return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickIsXbox
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickIsXbox(JNIEnv*, jclass,
|
||||
jbyte port) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickIsXbox";
|
||||
return HAL_GetJoystickIsXbox(port);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickType
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickType(JNIEnv*, jclass,
|
||||
jbyte port) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickType";
|
||||
return HAL_GetJoystickType(port);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickName
|
||||
* Signature: (B)Ljava/lang/String;
|
||||
*/
|
||||
JNIEXPORT jstring JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickName(JNIEnv* env, jclass,
|
||||
jbyte port) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickName";
|
||||
char *joystickName = HAL_GetJoystickName(port);
|
||||
jstring str = MakeJString(env, joystickName);
|
||||
HAL_FreeJoystickName(joystickName);
|
||||
return str;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetJoystickAxisType
|
||||
* Signature: (BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickAxisType(JNIEnv*, jclass,
|
||||
jbyte joystickNum,
|
||||
jbyte axis) {
|
||||
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickAxisType";
|
||||
return HAL_GetJoystickAxisType(joystickNum, axis);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: isNewControlData
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_isNewControlData(JNIEnv *, jclass) {
|
||||
return static_cast<jboolean>(HAL_IsNewControlData());
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: waitForDSData
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_waitForDSData(JNIEnv* env, jclass) {
|
||||
HAL_WaitForDSData();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: releaseDSMutex
|
||||
* Signature: ()V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_releaseDSMutex(JNIEnv* env, jclass) {
|
||||
HAL_ReleaseDSMutex();
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: waitForDSDataTimeout
|
||||
* Signature: (D)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_waitForDSDataTimeout(JNIEnv *, jclass,
|
||||
jdouble timeout) {
|
||||
return static_cast<jboolean>(HAL_WaitForDSDataTimeout(timeout));
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetMatchTime
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getMatchTime(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
return HAL_GetMatchTime(&status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetSystemActive
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getSystemActive(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetSystemActive(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_GetBrownedOut
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getBrownedOut(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetBrownedOut(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: getMatchInfo
|
||||
* Signature: (Ledu/wpi/first/wpilibj/hal/MatchInfoData;)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getMatchInfo
|
||||
(JNIEnv * env, jclass, jobject info) {
|
||||
HAL_MatchInfo matchInfo;
|
||||
auto status = HAL_GetMatchInfo(&matchInfo);
|
||||
if (status == 0) {
|
||||
SetMatchInfoObject(env, info, matchInfo);
|
||||
}
|
||||
HAL_FreeMatchInfo(&matchInfo);
|
||||
return status;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: HAL_SendError
|
||||
* Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_sendError(JNIEnv* env, jclass,
|
||||
jboolean isError, jint errorCode,
|
||||
jboolean isLVCode, jstring details,
|
||||
jstring location,
|
||||
jstring callStack,
|
||||
jboolean printMsg) {
|
||||
JStringRef detailsStr{env, details};
|
||||
JStringRef locationStr{env, location};
|
||||
JStringRef callStackStr{env, callStack};
|
||||
|
||||
NETCOMM_LOG(logDEBUG) << "Send Error: " << detailsStr.c_str();
|
||||
NETCOMM_LOG(logDEBUG) << "Location: " << locationStr.c_str();
|
||||
NETCOMM_LOG(logDEBUG) << "Call Stack: " << callStackStr.c_str();
|
||||
jint returnValue = HAL_SendError(isError, errorCode, isLVCode, detailsStr.c_str(),
|
||||
locationStr.c_str(), callStackStr.c_str(), printMsg);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: getPortWithModule
|
||||
* Signature: (BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HAL_getPortWithModule(
|
||||
JNIEnv* env, jclass, jbyte module, jbyte channel) {
|
||||
// FILE_LOG(logDEBUG) << "Calling HAL getPortWithModlue";
|
||||
// FILE_LOG(logDEBUG) << "Module = " << (jint)module;
|
||||
// FILE_LOG(logDEBUG) << "Channel = " << (jint)channel;
|
||||
HAL_PortHandle port = HAL_GetPortWithModule(module, channel);
|
||||
// FILE_LOG(logDEBUG) << "Port Handle = " << port;
|
||||
return (jint)port;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HAL
|
||||
* Method: getPort
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_HAL_getPort(
|
||||
JNIEnv* env, jclass, jbyte channel) {
|
||||
// FILE_LOG(logDEBUG) << "Calling HAL getPortWithModlue";
|
||||
// FILE_LOG(logDEBUG) << "Module = " << (jint)module;
|
||||
// FILE_LOG(logDEBUG) << "Channel = " << (jint)channel;
|
||||
HAL_PortHandle port = HAL_GetPort(channel);
|
||||
// FILE_LOG(logDEBUG) << "Port Handle = " << port;
|
||||
return (jint)port;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
456
hal/src/main/native/cpp/jni/HALUtil.cpp
Normal file
456
hal/src/main/native/cpp/jni/HALUtil.cpp
Normal file
@@ -0,0 +1,456 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HALUtil.h"
|
||||
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <jni.h>
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
#include <string>
|
||||
|
||||
#include "HAL/CAN.h"
|
||||
#include "HAL/HAL.h"
|
||||
#include "HAL/DriverStation.h"
|
||||
#include "HAL/Errors.h"
|
||||
#include "HAL/cpp/Log.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_HALUtil.h"
|
||||
#include "llvm/SmallString.h"
|
||||
#include "llvm/raw_ostream.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel halUtilLogLevel = logWARNING;
|
||||
|
||||
#define HALUTIL_LOG(level) \
|
||||
if (level > halUtilLogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
#define kRioStatusOffset -63000
|
||||
#define kRioStatusSuccess 0
|
||||
#define kRIOStatusBufferInvalidSize (kRioStatusOffset - 80)
|
||||
#define kRIOStatusOperationTimedOut -52007
|
||||
#define kRIOStatusFeatureNotSupported (kRioStatusOffset - 193)
|
||||
#define kRIOStatusResourceNotInitialized -52010
|
||||
|
||||
static JavaVM *jvm = nullptr;
|
||||
static JException runtimeExCls;
|
||||
static JException illegalArgExCls;
|
||||
static JException boundaryExCls;
|
||||
static JException allocationExCls;
|
||||
static JException halHandleExCls;
|
||||
static JException canInvalidBufferExCls;
|
||||
static JException canMessageNotFoundExCls;
|
||||
static JException canMessageNotAllowedExCls;
|
||||
static JException canNotInitializedExCls;
|
||||
static JException uncleanStatusExCls;
|
||||
static JClass pwmConfigDataResultCls;
|
||||
static JClass canStatusCls;
|
||||
static JClass matchInfoDataCls;
|
||||
static JClass accumulatorResultCls;
|
||||
|
||||
namespace frc {
|
||||
|
||||
void ThrowAllocationException(JNIEnv *env, int32_t minRange, int32_t maxRange,
|
||||
int32_t requestedValue, int32_t status) {
|
||||
const char *message = HAL_GetErrorMessage(status);
|
||||
llvm::SmallString<1024> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << " Code: " << status << ". " << message << ", Minimum Value: "
|
||||
<< minRange << ", Maximum Value: " << maxRange << ", Requested Value: "
|
||||
<< requestedValue;
|
||||
env->ThrowNew(allocationExCls, buf.c_str());
|
||||
allocationExCls.Throw(env, buf.c_str());
|
||||
}
|
||||
|
||||
void ThrowHalHandleException(JNIEnv *env, int32_t status) {
|
||||
const char *message = HAL_GetErrorMessage(status);
|
||||
llvm::SmallString<1024> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << " Code: " << status << ". " << message;
|
||||
halHandleExCls.Throw(env, buf.c_str());
|
||||
}
|
||||
|
||||
void ReportError(JNIEnv *env, int32_t status, bool doThrow) {
|
||||
if (status == 0) return;
|
||||
if (status == HAL_HANDLE_ERROR) {
|
||||
ThrowHalHandleException(env, status);
|
||||
}
|
||||
const char *message = HAL_GetErrorMessage(status);
|
||||
if (doThrow && status < 0) {
|
||||
llvm::SmallString<1024> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << " Code: " << status << ". " << message;
|
||||
runtimeExCls.Throw(env, buf.c_str());
|
||||
} else {
|
||||
std::string func;
|
||||
auto stack = GetJavaStackTrace(env, &func, "edu.wpi.first.wpilibj");
|
||||
HAL_SendError(1, status, 0, message, func.c_str(), stack.c_str(), 1);
|
||||
}
|
||||
}
|
||||
|
||||
void ThrowError(JNIEnv *env, int32_t status, int32_t minRange, int32_t maxRange,
|
||||
int32_t requestedValue) {
|
||||
if (status == 0) return;
|
||||
if (status == NO_AVAILABLE_RESOURCES ||
|
||||
status == RESOURCE_IS_ALLOCATED ||
|
||||
status == RESOURCE_OUT_OF_RANGE) {
|
||||
ThrowAllocationException(env, minRange, maxRange, requestedValue, status);
|
||||
}
|
||||
if (status == HAL_HANDLE_ERROR) {
|
||||
ThrowHalHandleException(env, status);
|
||||
}
|
||||
const char *message = HAL_GetErrorMessage(status);
|
||||
llvm::SmallString<1024> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << " Code: " << status << ". " << message;
|
||||
runtimeExCls.Throw(env, buf.c_str());
|
||||
}
|
||||
|
||||
void ReportCANError(JNIEnv *env, int32_t status, int message_id) {
|
||||
if (status >= 0) return;
|
||||
switch (status) {
|
||||
case kRioStatusSuccess:
|
||||
// Everything is ok... don't throw.
|
||||
break;
|
||||
case HAL_ERR_CANSessionMux_InvalidBuffer:
|
||||
case kRIOStatusBufferInvalidSize: {
|
||||
static jmethodID invalidBufConstruct = nullptr;
|
||||
if (!invalidBufConstruct)
|
||||
invalidBufConstruct =
|
||||
env->GetMethodID(canInvalidBufferExCls, "<init>", "()V");
|
||||
jobject exception =
|
||||
env->NewObject(canInvalidBufferExCls, invalidBufConstruct);
|
||||
env->Throw(static_cast<jthrowable>(exception));
|
||||
break;
|
||||
}
|
||||
case HAL_ERR_CANSessionMux_MessageNotFound:
|
||||
case kRIOStatusOperationTimedOut: {
|
||||
static jmethodID messageNotFoundConstruct = nullptr;
|
||||
if (!messageNotFoundConstruct)
|
||||
messageNotFoundConstruct =
|
||||
env->GetMethodID(canMessageNotFoundExCls, "<init>", "()V");
|
||||
jobject exception =
|
||||
env->NewObject(canMessageNotFoundExCls, messageNotFoundConstruct);
|
||||
env->Throw(static_cast<jthrowable>(exception));
|
||||
break;
|
||||
}
|
||||
case HAL_ERR_CANSessionMux_NotAllowed:
|
||||
case kRIOStatusFeatureNotSupported: {
|
||||
llvm::SmallString<100> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << "MessageID = " << message_id;
|
||||
canMessageNotAllowedExCls.Throw(env, buf.c_str());
|
||||
break;
|
||||
}
|
||||
case HAL_ERR_CANSessionMux_NotInitialized:
|
||||
case kRIOStatusResourceNotInitialized: {
|
||||
static jmethodID notInitConstruct = nullptr;
|
||||
if (!notInitConstruct)
|
||||
notInitConstruct =
|
||||
env->GetMethodID(canNotInitializedExCls, "<init>", "()V");
|
||||
jobject exception =
|
||||
env->NewObject(canNotInitializedExCls, notInitConstruct);
|
||||
env->Throw(static_cast<jthrowable>(exception));
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
llvm::SmallString<100> buf;
|
||||
llvm::raw_svector_ostream oss(buf);
|
||||
oss << "Fatal status code detected: " << status;
|
||||
uncleanStatusExCls.Throw(env, buf.c_str());
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ThrowIllegalArgumentException(JNIEnv *env, const char *msg) {
|
||||
illegalArgExCls.Throw(env, msg);
|
||||
}
|
||||
|
||||
void ThrowBoundaryException(JNIEnv *env, double value, double lower,
|
||||
double upper) {
|
||||
static jmethodID getMessage = nullptr;
|
||||
if (!getMessage)
|
||||
getMessage = env->GetStaticMethodID(boundaryExCls, "getMessage",
|
||||
"(DDD)Ljava/lang/String;");
|
||||
|
||||
static jmethodID constructor = nullptr;
|
||||
if (!constructor)
|
||||
constructor =
|
||||
env->GetMethodID(boundaryExCls, "<init>", "(Ljava/lang/String;)V");
|
||||
|
||||
jobject msg =
|
||||
env->CallStaticObjectMethod(boundaryExCls, getMessage,
|
||||
static_cast<jdouble>(value),
|
||||
static_cast<jdouble>(lower),
|
||||
static_cast<jdouble>(upper));
|
||||
jobject ex = env->NewObject(boundaryExCls, constructor, msg);
|
||||
env->Throw(static_cast<jthrowable>(ex));
|
||||
}
|
||||
|
||||
jobject CreatePWMConfigDataResult(JNIEnv *env, int32_t maxPwm,
|
||||
int32_t deadbandMaxPwm, int32_t centerPwm,
|
||||
int32_t deadbandMinPwm, int32_t minPwm) {
|
||||
static jmethodID constructor =
|
||||
env->GetMethodID(pwmConfigDataResultCls, "<init>",
|
||||
"(IIIII)V");
|
||||
return env->NewObject(pwmConfigDataResultCls, constructor, maxPwm,
|
||||
deadbandMaxPwm, centerPwm, deadbandMinPwm,
|
||||
minPwm);
|
||||
}
|
||||
|
||||
void SetCanStatusObject(JNIEnv *env, jobject canStatus,
|
||||
float percentBusUtilization,
|
||||
uint32_t busOffCount, uint32_t txFullCount,
|
||||
uint32_t receiveErrorCount,
|
||||
uint32_t transmitErrorCount) {
|
||||
static jmethodID func = env->GetMethodID(canStatusCls, "setStatus",
|
||||
"(DIIII)V");
|
||||
env->CallObjectMethod(canStatus, func, (jdouble)percentBusUtilization,
|
||||
(jint)busOffCount, (jint)txFullCount,
|
||||
(jint)receiveErrorCount, (jint)transmitErrorCount);
|
||||
}
|
||||
|
||||
void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
|
||||
const HAL_MatchInfo& matchInfo) {
|
||||
static jmethodID func = env->GetMethodID(matchInfoDataCls, "setData",
|
||||
"(Ljava/lang/String;Ljava/lang/String;III)V");
|
||||
|
||||
env->CallObjectMethod(matchStatus, func,
|
||||
MakeJString(env, matchInfo.eventName),
|
||||
MakeJString(env, matchInfo.gameSpecificMessage),
|
||||
(jint)matchInfo.matchNumber,
|
||||
(jint)matchInfo.replayNumber,
|
||||
(jint)matchInfo.matchType);
|
||||
}
|
||||
|
||||
void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
|
||||
int64_t value, int64_t count) {
|
||||
static jmethodID func = env->GetMethodID(accumulatorResultCls, "set",
|
||||
"(JJ)V");
|
||||
|
||||
env->CallObjectMethod(accumulatorResult, func, (jlong)value, (jlong)count);
|
||||
}
|
||||
|
||||
JavaVM* GetJVM() {
|
||||
return jvm;
|
||||
}
|
||||
|
||||
} // namespace frc
|
||||
|
||||
namespace sim {
|
||||
jint SimOnLoad(JavaVM* vm, void* reserved);
|
||||
void SimOnUnload(JavaVM* vm, void* reserved);
|
||||
}
|
||||
|
||||
using namespace frc;
|
||||
|
||||
extern "C" {
|
||||
|
||||
//
|
||||
// indicate JNI version support desired and load classes
|
||||
//
|
||||
JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM *vm, void *reserved) {
|
||||
jvm = vm;
|
||||
|
||||
// set our logging level
|
||||
Log::ReportingLevel() = logDEBUG;
|
||||
|
||||
JNIEnv *env;
|
||||
if (vm->GetEnv(reinterpret_cast<void **>(&env), JNI_VERSION_1_6) != JNI_OK)
|
||||
return JNI_ERR;
|
||||
|
||||
runtimeExCls = JException(env, "java/lang/RuntimeException");
|
||||
if (!runtimeExCls) return JNI_ERR;
|
||||
|
||||
illegalArgExCls = JException(env, "java/lang/IllegalArgumentException");
|
||||
if (!illegalArgExCls) return JNI_ERR;
|
||||
|
||||
boundaryExCls = JException(env, "edu/wpi/first/wpilibj/util/BoundaryException");
|
||||
if (!boundaryExCls) return JNI_ERR;
|
||||
|
||||
allocationExCls = JException(env, "edu/wpi/first/wpilibj/util/AllocationException");
|
||||
if (!allocationExCls) return JNI_ERR;
|
||||
|
||||
halHandleExCls = JException(env, "edu/wpi/first/wpilibj/util/HalHandleException");
|
||||
if (!halHandleExCls) return JNI_ERR;
|
||||
|
||||
canInvalidBufferExCls = JException(env, "edu/wpi/first/wpilibj/can/CANInvalidBufferException");
|
||||
if (!canInvalidBufferExCls) return JNI_ERR;
|
||||
|
||||
canMessageNotFoundExCls = JException(env, "edu/wpi/first/wpilibj/can/CANMessageNotFoundException");
|
||||
if (!canMessageNotFoundExCls) return JNI_ERR;
|
||||
|
||||
canMessageNotAllowedExCls = JException(env, "edu/wpi/first/wpilibj/can/CANMessageNotAllowedException");
|
||||
if (!canMessageNotAllowedExCls) return JNI_ERR;
|
||||
|
||||
canNotInitializedExCls = JException(env, "edu/wpi/first/wpilibj/can/CANNotInitializedException");
|
||||
if (!canNotInitializedExCls) return JNI_ERR;
|
||||
|
||||
uncleanStatusExCls = JException(env,"edu/wpi/first/wpilibj/util/UncleanStatusException");
|
||||
if (!uncleanStatusExCls) return JNI_ERR;
|
||||
|
||||
pwmConfigDataResultCls = JClass(env, "edu/wpi/first/wpilibj/PWMConfigDataResult");
|
||||
if (!pwmConfigDataResultCls) return JNI_ERR;
|
||||
|
||||
canStatusCls = JClass(env, "edu/wpi/first/wpilibj/can/CANStatus");
|
||||
if (!canStatusCls) return JNI_ERR;
|
||||
|
||||
matchInfoDataCls = JClass(env, "edu/wpi/first/wpilibj/hal/MatchInfoData");
|
||||
if (!matchInfoDataCls) return JNI_ERR;
|
||||
|
||||
accumulatorResultCls = JClass(env, "edu/wpi/first/wpilibj/AccumulatorResult");
|
||||
if (!accumulatorResultCls) return JNI_ERR;
|
||||
|
||||
return sim::SimOnLoad(vm, reserved);
|
||||
}
|
||||
|
||||
JNIEXPORT void JNICALL JNI_OnUnload(JavaVM *vm, void *reserved) {
|
||||
sim::SimOnUnload(vm, reserved);
|
||||
|
||||
JNIEnv *env;
|
||||
if (vm->GetEnv(reinterpret_cast<void **>(&env), JNI_VERSION_1_6) != JNI_OK)
|
||||
return;
|
||||
// Delete global references
|
||||
runtimeExCls.free(env);
|
||||
illegalArgExCls.free(env);
|
||||
boundaryExCls.free(env);
|
||||
allocationExCls.free(env);
|
||||
halHandleExCls.free(env);
|
||||
canInvalidBufferExCls.free(env);
|
||||
canMessageNotFoundExCls.free(env);
|
||||
canMessageNotAllowedExCls.free(env);
|
||||
canNotInitializedExCls.free(env);
|
||||
uncleanStatusExCls.free(env);
|
||||
pwmConfigDataResultCls.free(env);
|
||||
canStatusCls.free(env);
|
||||
matchInfoDataCls.free(env);
|
||||
jvm = nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getFPGAVersion
|
||||
* Signature: ()S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getFPGAVersion(JNIEnv *env, jclass) {
|
||||
HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGAVersion";
|
||||
int32_t status = 0;
|
||||
jshort returnValue = HAL_GetFPGAVersion(&status);
|
||||
HALUTIL_LOG(logDEBUG) << "Status = " << status;
|
||||
HALUTIL_LOG(logDEBUG) << "FPGAVersion = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getFPGARevision
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getFPGARevision(JNIEnv *env, jclass) {
|
||||
HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGARevision";
|
||||
int32_t status = 0;
|
||||
jint returnValue = HAL_GetFPGARevision(&status);
|
||||
HALUTIL_LOG(logDEBUG) << "Status = " << status;
|
||||
HALUTIL_LOG(logDEBUG) << "FPGARevision = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getFPGATime
|
||||
* Signature: ()J
|
||||
*/
|
||||
JNIEXPORT jlong JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getFPGATime(JNIEnv *env, jclass) {
|
||||
// HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGATime";
|
||||
int32_t status = 0;
|
||||
jlong returnValue = HAL_GetFPGATime(&status);
|
||||
// HALUTIL_LOG(logDEBUG) << "Status = " << status;
|
||||
// HALUTIL_LOG(logDEBUG) << "FPGATime = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getHALRuntimeType
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getHALRuntimeType(JNIEnv *env, jclass) {
|
||||
// HALUTIL_LOG(logDEBUG) << "Calling HALUtil getHALRuntimeType";
|
||||
jint returnValue = HAL_GetRuntimeType();
|
||||
// HALUTIL_LOG(logDEBUG) << "RuntimeType = " << returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getFPGAButton
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getFPGAButton(JNIEnv *env, jclass) {
|
||||
// HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGATime";
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetFPGAButton(&status);
|
||||
// HALUTIL_LOG(logDEBUG) << "Status = " << status;
|
||||
// HALUTIL_LOG(logDEBUG) << "FPGATime = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getHALErrorMessage
|
||||
* Signature: (I)Ljava/lang/String;
|
||||
*/
|
||||
JNIEXPORT jstring JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getHALErrorMessage(
|
||||
JNIEnv *paramEnv, jclass, jint paramId) {
|
||||
const char *msg = HAL_GetErrorMessage(paramId);
|
||||
HALUTIL_LOG(logDEBUG) << "Calling HALUtil HAL_GetErrorMessage id=" << paramId
|
||||
<< " msg=" << msg;
|
||||
return MakeJString(paramEnv, msg);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getHALErrno
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_HALUtil_getHALErrno(JNIEnv *, jclass) {
|
||||
return errno;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_HALUtil
|
||||
* Method: getHALstrerror
|
||||
* Signature: (I)Ljava/lang/String;
|
||||
*/
|
||||
JNIEXPORT jstring JNICALL Java_edu_wpi_first_wpilibj_hal_HALUtil_getHALstrerror(
|
||||
JNIEnv *env, jclass, jint errorCode) {
|
||||
const char *msg = strerror(errno);
|
||||
HALUTIL_LOG(logDEBUG) << "Calling HALUtil getHALstrerror errorCode="
|
||||
<< errorCode << " msg=" << msg;
|
||||
return MakeJString(env, msg);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
71
hal/src/main/native/cpp/jni/HALUtil.h
Normal file
71
hal/src/main/native/cpp/jni/HALUtil.h
Normal file
@@ -0,0 +1,71 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#ifndef HALUTIL_H
|
||||
#define HALUTIL_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <jni.h>
|
||||
|
||||
struct HAL_MatchInfo;
|
||||
|
||||
namespace frc {
|
||||
|
||||
void ReportError(JNIEnv *env, int32_t status, bool doThrow = true);
|
||||
|
||||
void ThrowError(JNIEnv *env, int32_t status, int32_t minRange, int32_t maxRange,
|
||||
int32_t requestedValue);
|
||||
|
||||
inline bool CheckStatus(JNIEnv *env, int32_t status, bool doThrow = true) {
|
||||
if (status != 0) ReportError(env, status, doThrow);
|
||||
return status == 0;
|
||||
}
|
||||
|
||||
inline bool CheckStatusRange(JNIEnv *env, int32_t status, int32_t minRange,
|
||||
int32_t maxRange, int32_t requestedValue) {
|
||||
if (status != 0) ThrowError(env, status, minRange, maxRange, requestedValue);
|
||||
return status == 0;
|
||||
}
|
||||
|
||||
inline bool CheckStatusForceThrow(JNIEnv *env, int32_t status) {
|
||||
if (status != 0) ThrowError(env, status, 0, 0, 0);
|
||||
return status == 0;
|
||||
}
|
||||
|
||||
void ReportCANError(JNIEnv *env, int32_t status, int32_t message_id);
|
||||
|
||||
inline bool CheckCANStatus(JNIEnv *env, int32_t status, int32_t message_id) {
|
||||
if (status != 0) ReportCANError(env, status, message_id);
|
||||
return status == 0;
|
||||
}
|
||||
|
||||
void ThrowIllegalArgumentException(JNIEnv *env, const char *msg);
|
||||
void ThrowBoundaryException(JNIEnv *env, double value, double lower,
|
||||
double upper);
|
||||
|
||||
jobject CreatePWMConfigDataResult(JNIEnv *env, int32_t maxPwm,
|
||||
int32_t deadbandMaxPwm, int32_t centerPwm,
|
||||
int32_t deadbandMinPwm, int32_t minPwm);
|
||||
|
||||
void SetCanStatusObject(JNIEnv *env, jobject canStatus,
|
||||
float percentBusUtilization,
|
||||
uint32_t busOffCount, uint32_t txFullCount,
|
||||
uint32_t receiveErrorCount,
|
||||
uint32_t transmitErrorCount);
|
||||
|
||||
void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
|
||||
const HAL_MatchInfo& matchInfo);
|
||||
|
||||
void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
|
||||
int64_t value, int64_t count);
|
||||
|
||||
JavaVM* GetJVM();
|
||||
|
||||
} // namespace frc
|
||||
|
||||
#endif // HALUTIL_H
|
||||
196
hal/src/main/native/cpp/jni/I2CJNI.cpp
Normal file
196
hal/src/main/native/cpp/jni/I2CJNI.cpp
Normal file
@@ -0,0 +1,196 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_I2CJNI.h"
|
||||
|
||||
#include "HAL/I2C.h"
|
||||
#include "HALUtil.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel i2cJNILogLevel = logWARNING;
|
||||
|
||||
#define I2CJNI_LOG(level) \
|
||||
if (level > i2cJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2cInitialize
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CInitialize(
|
||||
JNIEnv* env, jclass, jint port) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CInititalize";
|
||||
I2CJNI_LOG(logDEBUG) << "Port: " << port;
|
||||
int32_t status = 0;
|
||||
HAL_InitializeI2C(static_cast<HAL_I2CPort>(port), &status);
|
||||
I2CJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatusForceThrow(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CTransaction
|
||||
* Signature: (IBLjava/nio/ByteBuffer;BLjava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CTransaction(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
|
||||
jbyte sendSize, jobject dataReceived, jbyte receiveSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CTransaction";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
|
||||
uint8_t* dataToSendPtr = nullptr;
|
||||
if (dataToSend != 0) {
|
||||
dataToSendPtr = (uint8_t*)env->GetDirectBufferAddress(dataToSend);
|
||||
}
|
||||
I2CJNI_LOG(logDEBUG) << "DataToSendPtr = " << (jint*)dataToSendPtr;
|
||||
I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
|
||||
uint8_t* dataReceivedPtr =
|
||||
(uint8_t*)env->GetDirectBufferAddress(dataReceived);
|
||||
I2CJNI_LOG(logDEBUG) << "DataReceivedPtr = " << (jint*)dataReceivedPtr;
|
||||
I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << (jint)receiveSize;
|
||||
jint returnValue = HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address, dataToSendPtr, sendSize,
|
||||
dataReceivedPtr, receiveSize);
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CTransactionB
|
||||
* Signature: (IB[BB[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CTransactionB(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
|
||||
jbyte sendSize, jbyteArray dataReceived, jbyte receiveSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CTransactionB";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
|
||||
I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
|
||||
llvm::SmallVector<uint8_t, 128> recvBuf;
|
||||
recvBuf.resize(receiveSize);
|
||||
I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << (jint)receiveSize;
|
||||
jint returnValue =
|
||||
HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address,
|
||||
reinterpret_cast<const uint8_t *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
sendSize, recvBuf.data(), receiveSize);
|
||||
env->SetByteArrayRegion(dataReceived, 0, receiveSize,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CWrite
|
||||
* Signature: (IBLjava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CWrite(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
|
||||
jbyte sendSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CWrite";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
|
||||
uint8_t* dataToSendPtr = nullptr;
|
||||
|
||||
if (dataToSend != 0) {
|
||||
dataToSendPtr = (uint8_t*)env->GetDirectBufferAddress(dataToSend);
|
||||
}
|
||||
I2CJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
|
||||
I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
|
||||
jint returnValue = HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address, dataToSendPtr, sendSize);
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CWriteB
|
||||
* Signature: (IB[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CWriteB(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
|
||||
jbyte sendSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CWrite";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
|
||||
I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
|
||||
jint returnValue =
|
||||
HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address,
|
||||
reinterpret_cast<const uint8_t *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
sendSize);
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CRead
|
||||
* Signature: (IBLjava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CRead(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jobject dataReceived,
|
||||
jbyte receiveSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CRead";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << address;
|
||||
uint8_t* dataReceivedPtr =
|
||||
(uint8_t*)env->GetDirectBufferAddress(dataReceived);
|
||||
I2CJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
|
||||
I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << receiveSize;
|
||||
jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address, dataReceivedPtr, receiveSize);
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CReadB
|
||||
* Signature: (IB[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CReadB(
|
||||
JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataReceived,
|
||||
jbyte receiveSize) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CRead";
|
||||
I2CJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
I2CJNI_LOG(logDEBUG) << "Address = " << address;
|
||||
I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << receiveSize;
|
||||
llvm::SmallVector<uint8_t, 128> recvBuf;
|
||||
recvBuf.resize(receiveSize);
|
||||
jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address, recvBuf.data(), receiveSize);
|
||||
env->SetByteArrayRegion(dataReceived, 0, receiveSize,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_I2CJNI
|
||||
* Method: i2CClose
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_I2CJNI_i2CClose(JNIEnv*, jclass, jint port) {
|
||||
I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CClose";
|
||||
HAL_CloseI2C(static_cast<HAL_I2CPort>(port));
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
347
hal/src/main/native/cpp/jni/InterruptJNI.cpp
Normal file
347
hal/src/main/native/cpp/jni/InterruptJNI.cpp
Normal file
@@ -0,0 +1,347 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include <atomic>
|
||||
#include <thread>
|
||||
|
||||
#include <support/mutex.h>
|
||||
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "HAL/Interrupts.h"
|
||||
#include "HALUtil.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_InterruptJNI.h"
|
||||
#include "support/SafeThread.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
TLogLevel interruptJNILogLevel = logERROR;
|
||||
|
||||
#define INTERRUPTJNI_LOG(level) \
|
||||
if (level > interruptJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
// Thread where callbacks are actually performed.
|
||||
//
|
||||
// JNI's AttachCurrentThread() creates a Java Thread object on every
|
||||
// invocation, which is both time inefficient and causes issues with Eclipse
|
||||
// (which tries to keep a thread list up-to-date and thus gets swamped).
|
||||
//
|
||||
// Instead, this class attaches just once. When a hardware notification
|
||||
// occurs, a condition variable wakes up this thread and this thread actually
|
||||
// makes the call into Java.
|
||||
//
|
||||
// We don't want to use a FIFO here. If the user code takes too long to
|
||||
// process, we will just ignore the redundant wakeup.
|
||||
class InterruptThreadJNI : public wpi::SafeThread {
|
||||
public:
|
||||
void Main();
|
||||
|
||||
bool m_notify = false;
|
||||
uint32_t m_mask = 0;
|
||||
jobject m_func = nullptr;
|
||||
jmethodID m_mid;
|
||||
jobject m_param = nullptr;
|
||||
};
|
||||
|
||||
class InterruptJNI : public wpi::SafeThreadOwner<InterruptThreadJNI> {
|
||||
public:
|
||||
void SetFunc(JNIEnv* env, jobject func, jmethodID mid, jobject param);
|
||||
|
||||
void Notify(uint32_t mask) {
|
||||
auto thr = GetThread();
|
||||
if (!thr) return;
|
||||
thr->m_notify = true;
|
||||
thr->m_mask = mask;
|
||||
thr->m_cond.notify_one();
|
||||
}
|
||||
};
|
||||
|
||||
void InterruptJNI::SetFunc(JNIEnv* env, jobject func, jmethodID mid,
|
||||
jobject param) {
|
||||
auto thr = GetThread();
|
||||
if (!thr) return;
|
||||
// free global references
|
||||
if (thr->m_func) env->DeleteGlobalRef(thr->m_func);
|
||||
if (thr->m_param) env->DeleteGlobalRef(thr->m_param);
|
||||
// create global references
|
||||
thr->m_func = env->NewGlobalRef(func);
|
||||
thr->m_param = param ? env->NewGlobalRef(param) : nullptr;
|
||||
thr->m_mid = mid;
|
||||
}
|
||||
|
||||
void InterruptThreadJNI::Main() {
|
||||
JNIEnv* env;
|
||||
JavaVMAttachArgs args;
|
||||
args.version = JNI_VERSION_1_2;
|
||||
args.name = const_cast<char*>("Interrupt");
|
||||
args.group = nullptr;
|
||||
jint rs = GetJVM()->AttachCurrentThreadAsDaemon(reinterpret_cast<void**>(&env),
|
||||
&args);
|
||||
if (rs != JNI_OK) return;
|
||||
|
||||
std::unique_lock<wpi::mutex> lock(m_mutex);
|
||||
while (m_active) {
|
||||
m_cond.wait(lock, [&] { return !m_active || m_notify; });
|
||||
if (!m_active) break;
|
||||
m_notify = false;
|
||||
if (!m_func) continue;
|
||||
jobject func = m_func;
|
||||
jmethodID mid = m_mid;
|
||||
uint32_t mask = m_mask;
|
||||
jobject param = m_param;
|
||||
lock.unlock(); // don't hold mutex during callback execution
|
||||
env->CallVoidMethod(func, mid, static_cast<jint>(mask), param);
|
||||
if (env->ExceptionCheck()) {
|
||||
env->ExceptionDescribe();
|
||||
env->ExceptionClear();
|
||||
}
|
||||
lock.lock();
|
||||
}
|
||||
|
||||
// free global references
|
||||
if (m_func) env->DeleteGlobalRef(m_func);
|
||||
if (m_param) env->DeleteGlobalRef(m_param);
|
||||
|
||||
GetJVM()->DetachCurrentThread();
|
||||
}
|
||||
|
||||
void interruptHandler(uint32_t mask, void* param) {
|
||||
static_cast<InterruptJNI*>(param)->Notify(mask);
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: initializeInterrupts
|
||||
* Signature: (Z)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_initializeInterrupts(
|
||||
JNIEnv* env, jclass, jboolean watcher) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI initializeInterrupts";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "watcher = " << (bool)watcher;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_InterruptHandle interrupt = HAL_InitializeInterrupts(watcher, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << interrupt;
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
CheckStatusForceThrow(env, status);
|
||||
return (jint)interrupt;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: cleanInterrupts
|
||||
* Signature: (J)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_cleanInterrupts(
|
||||
JNIEnv* env, jclass, jint interruptHandle) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI cleanInterrupts";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_CleanInterrupts((HAL_InterruptHandle)interruptHandle, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
// ignore status, as an invalid handle just needs to be ignored.
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: waitForInterrupt
|
||||
* Signature: (JD)V
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_waitForInterrupt(
|
||||
JNIEnv* env, jclass, jint interruptHandle, jdouble timeout,
|
||||
jboolean ignorePrevious) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI waitForInterrupt";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
int32_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle,
|
||||
timeout, ignorePrevious, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
CheckStatus(env, status);
|
||||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: enableInterrupts
|
||||
* Signature: (J)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_enableInterrupts(
|
||||
JNIEnv* env, jclass, jint interruptHandle) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI enableInterrupts";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_EnableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: disableInterrupts
|
||||
* Signature: (J)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_disableInterrupts(
|
||||
JNIEnv* env, jclass, jint interruptHandle) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI disableInterrupts";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_DisableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: readInterruptRisingTimestamp
|
||||
* Signature: (J)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_readInterruptRisingTimestamp(
|
||||
JNIEnv* env, jclass, jint interruptHandle) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI readInterruptRisingTimestamp";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
jdouble timeStamp = HAL_ReadInterruptRisingTimestamp((HAL_InterruptHandle)interruptHandle, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return timeStamp;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: readInterruptFallingTimestamp
|
||||
* Signature: (J)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_readInterruptFallingTimestamp(
|
||||
JNIEnv* env, jclass, jint interruptHandle) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI readInterruptFallingTimestamp";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
jdouble timeStamp = HAL_ReadInterruptFallingTimestamp((HAL_InterruptHandle)interruptHandle, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return timeStamp;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: requestInterrupts
|
||||
* Signature: (III)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_requestInterrupts(
|
||||
JNIEnv* env, jclass, jint interruptHandle, jint digitalSourceHandle,
|
||||
jint analogTriggerType) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI requestInterrupts";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_RequestInterrupts((HAL_InterruptHandle)interruptHandle, (HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType, &status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: attachInterruptHandler
|
||||
* Signature:
|
||||
* (JLedu/wpi/first/wpilibj/hal/InterruptJNI/InterruptHandlerFunction;Ljava/nio/ByteBuffer;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_attachInterruptHandler(
|
||||
JNIEnv* env, jclass, jint interruptHandle, jobject handler,
|
||||
jobject param) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI attachInterruptHandler";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
|
||||
jclass cls = env->GetObjectClass(handler);
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "class = " << cls;
|
||||
if (cls == 0) {
|
||||
INTERRUPTJNI_LOG(logERROR) << "Error getting java class";
|
||||
assert(false);
|
||||
return;
|
||||
}
|
||||
jmethodID mid = env->GetMethodID(cls, "apply", "(ILjava/lang/Object;)V");
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "method = " << mid;
|
||||
if (mid == 0) {
|
||||
INTERRUPTJNI_LOG(logERROR) << "Error getting java method ID";
|
||||
assert(false);
|
||||
return;
|
||||
}
|
||||
|
||||
InterruptJNI* intr = new InterruptJNI;
|
||||
intr->Start();
|
||||
intr->SetFunc(env, handler, mid, param);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "InterruptThreadJNI Ptr = " << intr;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_AttachInterruptHandler((HAL_InterruptHandle)interruptHandle, interruptHandler, intr,
|
||||
&status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_InterruptJNI
|
||||
* Method: setInterruptUpSourceEdge
|
||||
* Signature: (JZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_InterruptJNI_setInterruptUpSourceEdge(
|
||||
JNIEnv* env, jclass, jint interruptHandle, jboolean risingEdge,
|
||||
jboolean fallingEdge) {
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI setInterruptUpSourceEdge";
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Rising Edge = " << (bool)risingEdge;
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Falling Edge = " << (bool)fallingEdge;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_SetInterruptUpSourceEdge((HAL_InterruptHandle)interruptHandle, risingEdge, fallingEdge,
|
||||
&status);
|
||||
|
||||
INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
147
hal/src/main/native/cpp/jni/NotifierJNI.cpp
Normal file
147
hal/src/main/native/cpp/jni/NotifierJNI.cpp
Normal file
@@ -0,0 +1,147 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/Notifier.h"
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include <stdio.h>
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/cpp/Log.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_NotifierJNI.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel notifierJNILogLevel = logWARNING;
|
||||
|
||||
#define NOTIFIERJNI_LOG(level) \
|
||||
if (level > notifierJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: initializeNotifier
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_NotifierJNI_initializeNotifier(
|
||||
JNIEnv *env, jclass) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI initializeNotifier";
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_NotifierHandle notifierHandle = HAL_InitializeNotifier(&status);
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
|
||||
if (notifierHandle <= 0 || !CheckStatusForceThrow(env, status)) {
|
||||
return 0; // something went wrong in HAL
|
||||
}
|
||||
|
||||
return (jint)notifierHandle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: stopNotifier
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_NotifierJNI_stopNotifier(
|
||||
JNIEnv *env, jclass cls, jint notifierHandle) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI stopNotifier";
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_StopNotifier((HAL_NotifierHandle)notifierHandle, &status);
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: cleanNotifier
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_NotifierJNI_cleanNotifier(
|
||||
JNIEnv *env, jclass, jint notifierHandle) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI cleanNotifier";
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_CleanNotifier((HAL_NotifierHandle)notifierHandle, &status);
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: updateNotifierAlarm
|
||||
* Signature: (IJ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_NotifierJNI_updateNotifierAlarm(
|
||||
JNIEnv *env, jclass cls, jint notifierHandle, jlong triggerTime) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI updateNotifierAlarm";
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "triggerTime = " << triggerTime;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_UpdateNotifierAlarm((HAL_NotifierHandle)notifierHandle, (uint64_t)triggerTime, &status);
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: cancelNotifierAlarm
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_NotifierJNI_cancelNotifierAlarm(
|
||||
JNIEnv *env, jclass cls, jint notifierHandle) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI cancelNotifierAlarm";
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_CancelNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_NotifierJNI
|
||||
* Method: waitForNotifierAlarm
|
||||
* Signature: (I)J
|
||||
*/
|
||||
JNIEXPORT jlong JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_NotifierJNI_waitForNotifierAlarm(
|
||||
JNIEnv *env, jclass cls, jint notifierHandle) {
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI waitForNotifierAlarm";
|
||||
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
|
||||
|
||||
int32_t status = 0;
|
||||
uint64_t time =
|
||||
HAL_WaitForNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
NOTIFIERJNI_LOG(logDEBUG) << "Time = " << time;
|
||||
CheckStatus(env, status);
|
||||
|
||||
return (jlong)time;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
322
hal/src/main/native/cpp/jni/OSSerialPortJNI.cpp
Normal file
322
hal/src/main/native/cpp/jni/OSSerialPortJNI.cpp
Normal file
@@ -0,0 +1,322 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_OSSerialPortJNI.h"
|
||||
|
||||
#include "HAL/OSSerialPort.h"
|
||||
#include "HALUtil.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel osserialJNILogLevel = logWARNING;
|
||||
|
||||
#define SERIALJNI_LOG(level) \
|
||||
if (level > osserialJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialInitializePort
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialInitializePort(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize";
|
||||
SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
int32_t status = 0;
|
||||
HAL_InitializeOSSerialPort(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatusForceThrow(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetBaudRate
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetBaudRate(
|
||||
JNIEnv* env, jclass, jbyte port, jint rate) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Baud Rate";
|
||||
SERIALJNI_LOG(logDEBUG) << "Baud: " << rate;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialBaudRate(static_cast<HAL_SerialPort>(port), rate, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetDataBits
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetDataBits(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte bits) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Data Bits";
|
||||
SERIALJNI_LOG(logDEBUG) << "Data Bits: " << bits;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialDataBits(static_cast<HAL_SerialPort>(port), bits, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetParity
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetParity(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte parity) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Parity";
|
||||
SERIALJNI_LOG(logDEBUG) << "Parity: " << parity;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetStopBits
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetStopBits(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte bits) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Stop Bits";
|
||||
SERIALJNI_LOG(logDEBUG) << "Stop Bits: " << bits;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialStopBits(static_cast<HAL_SerialPort>(port), bits, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetWriteMode
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetWriteMode(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte mode) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Mode";
|
||||
SERIALJNI_LOG(logDEBUG) << "Write mode: " << mode;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialWriteMode(static_cast<HAL_SerialPort>(port), mode, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetFlowControl
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetFlowControl(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte flow) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Flow Control";
|
||||
SERIALJNI_LOG(logDEBUG) << "Flow Control: " << flow;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialFlowControl(static_cast<HAL_SerialPort>(port), flow, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetTimeout
|
||||
* Signature: (BD)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetTimeout(
|
||||
JNIEnv* env, jclass, jbyte port, jdouble timeout) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Timeout";
|
||||
SERIALJNI_LOG(logDEBUG) << "Timeout: " << timeout;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialTimeout(static_cast<HAL_SerialPort>(port), timeout, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialEnableTermination
|
||||
* Signature: (BC)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialEnableTermination(
|
||||
JNIEnv* env, jclass, jbyte port, jchar terminator) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Enable Termination";
|
||||
SERIALJNI_LOG(logDEBUG) << "Terminator: " << terminator;
|
||||
int32_t status = 0;
|
||||
HAL_EnableOSSerialTermination(static_cast<HAL_SerialPort>(port), terminator, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialDisableTermination
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialDisableTermination(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Disable termination";
|
||||
int32_t status = 0;
|
||||
HAL_DisableOSSerialTermination(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetReadBufferSize
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetReadBufferSize(
|
||||
JNIEnv* env, jclass, jbyte port, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Read Buffer Size";
|
||||
SERIALJNI_LOG(logDEBUG) << "Size: " << size;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialReadBufferSize(static_cast<HAL_SerialPort>(port), size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialSetWriteBufferSize
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialSetWriteBufferSize(
|
||||
JNIEnv* env, jclass, jbyte port, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Buffer Size";
|
||||
SERIALJNI_LOG(logDEBUG) << "Size: " << size;
|
||||
int32_t status = 0;
|
||||
HAL_SetOSSerialWriteBufferSize(static_cast<HAL_SerialPort>(port), size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialGetBytesReceived
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialGetBytesReceived(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Get Bytes Received";
|
||||
int32_t status = 0;
|
||||
jint retVal = HAL_GetOSSerialBytesReceived(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialRead
|
||||
* Signature: (B[BI)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialRead(
|
||||
JNIEnv* env, jclass, jbyte port, jbyteArray dataReceived, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Read";
|
||||
llvm::SmallVector<char, 128> recvBuf;
|
||||
recvBuf.resize(size);
|
||||
int32_t status = 0;
|
||||
jint retVal = HAL_ReadOSSerial(static_cast<HAL_SerialPort>(port), recvBuf.data(),
|
||||
size, &status);
|
||||
env->SetByteArrayRegion(dataReceived, 0, size,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialWrite
|
||||
* Signature: (B[BI)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialWrite(
|
||||
JNIEnv* env, jclass, jbyte port, jbyteArray dataToSend, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Write";
|
||||
int32_t status = 0;
|
||||
jint retVal =
|
||||
HAL_WriteOSSerial(static_cast<HAL_SerialPort>(port),
|
||||
reinterpret_cast<const char *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialFlush
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialFlush(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Flush";
|
||||
int32_t status = 0;
|
||||
HAL_FlushOSSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialClear
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialClear(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Clear";
|
||||
int32_t status = 0;
|
||||
HAL_ClearOSSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_OSSerialPortJNI
|
||||
* Method: serialClose
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_OSSerialPortJNI_serialClose(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Close";
|
||||
int32_t status = 0;
|
||||
HAL_CloseOSSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
158
hal/src/main/native/cpp/jni/PDPJNI.cpp
Normal file
158
hal/src/main/native/cpp/jni/PDPJNI.cpp
Normal file
@@ -0,0 +1,158 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/PDP.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HALUtil.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_PDPJNI.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPTemperature
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PDPJNI_initializePDP(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
HAL_InitializePDP(module, &status);
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumPDPModules(), module);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: checkPDPChannel
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_PDPJNI_checkPDPChannel(
|
||||
JNIEnv *env, jclass, jint channel) {
|
||||
return HAL_CheckPDPChannel(channel);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: checkPDPModule
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_PDPJNI_checkPDPModule(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
return HAL_CheckPDPModule(module);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPTemperature
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPTemperature(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
double temperature = HAL_GetPDPTemperature(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return temperature;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPVoltage
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPVoltage(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
double voltage = HAL_GetPDPVoltage(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return voltage;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPChannelCurrent
|
||||
* Signature: (BI)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPChannelCurrent(
|
||||
JNIEnv *env, jclass, jbyte channel, jint module) {
|
||||
int32_t status = 0;
|
||||
double current = HAL_GetPDPChannelCurrent(module, channel, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return current;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPTotalCurrent
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPTotalCurrent(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
double current = HAL_GetPDPTotalCurrent(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return current;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: getPDPTotalPower
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPTotalPower(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
double power = HAL_GetPDPTotalPower(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return power;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: resetPDPTotalEnergy
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_getPDPTotalEnergy(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
double energy = HAL_GetPDPTotalEnergy(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
return energy;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: resetPDPTotalEnergy
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_resetPDPTotalEnergy(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
HAL_ResetPDPTotalEnergy(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PDPJNI
|
||||
* Method: clearStickyFaults
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PDPJNI_clearPDPStickyFaults(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
HAL_ClearPDPStickyFaults(module, &status);
|
||||
CheckStatus(env, status, false);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
300
hal/src/main/native/cpp/jni/PWMJNI.cpp
Normal file
300
hal/src/main/native/cpp/jni/PWMJNI.cpp
Normal file
@@ -0,0 +1,300 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_PWMJNI.h"
|
||||
|
||||
#include "HAL/DIO.h"
|
||||
#include "HAL/PWM.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel pwmJNILogLevel = logWARNING;
|
||||
|
||||
#define PWMJNI_LOG(level) \
|
||||
if (level > pwmJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: initializePWMPort
|
||||
* Signature: (I)I;
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PWMJNI_initializePWMPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI initializePWMPort";
|
||||
PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
int32_t status = 0;
|
||||
auto pwm = HAL_InitializePWMPort((HAL_PortHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << pwm;
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumPWMChannels(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jint)pwm;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: checkPWMChannel
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_checkPWMChannel(
|
||||
JNIEnv *env, jclass, jint channel) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI checkPWMChannel";
|
||||
PWMJNI_LOG(logDEBUG) << "Channel = " << channel;
|
||||
return HAL_CheckPWMChannel(channel);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: freeDIOPort
|
||||
* Signature: (I)V;
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_freePWMPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI freePWMPort";
|
||||
PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_FreePWMPort((HAL_DigitalHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setPWMConfigRaw
|
||||
* Signature: (IIIIII)V;
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMConfigRaw(
|
||||
JNIEnv *env, jclass, jint id, jint maxPwm, jint deadbandMaxPwm,
|
||||
jint centerPwm, jint deadbandMinPwm, jint minPwm) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI setPWMConfigRaw";
|
||||
PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMConfigRaw((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
|
||||
deadbandMinPwm, minPwm, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: setPWMConfig
|
||||
* Signature: (IDDDDD)V;
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMConfig(
|
||||
JNIEnv *env, jclass, jint id, jdouble maxPwm, jdouble deadbandMaxPwm,
|
||||
jdouble centerPwm, jdouble deadbandMinPwm, jdouble minPwm) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI setPWMConfig";
|
||||
PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMConfig((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
|
||||
deadbandMinPwm, minPwm, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
|
||||
* Method: getPWMConfigRaw
|
||||
* Signature: (I)Ledu/wpi/first/wpilibj/PWMConfigDataResult;
|
||||
*/
|
||||
JNIEXPORT jobject JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMConfigRaw(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "Calling PWMJNI getPWMConfigRaw";
|
||||
PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
int32_t maxPwm = 0;
|
||||
int32_t deadbandMaxPwm = 0;
|
||||
int32_t centerPwm = 0;
|
||||
int32_t deadbandMinPwm = 0;
|
||||
int32_t minPwm = 0;
|
||||
HAL_GetPWMConfigRaw((HAL_DigitalHandle)id, &maxPwm, &deadbandMaxPwm, ¢erPwm,
|
||||
&deadbandMinPwm, &minPwm, &status);
|
||||
CheckStatus(env, status);
|
||||
return CreatePWMConfigDataResult(env, maxPwm, deadbandMaxPwm, centerPwm,
|
||||
deadbandMinPwm, minPwm);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMEliminateDeadband
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMEliminateDeadband(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMEliminateDeadband((HAL_DigitalHandle)id, value, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: getPWMEliminateDeadband
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMEliminateDeadband(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
auto val = HAL_GetPWMEliminateDeadband((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return (jboolean)val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMRaw
|
||||
* Signature: (IS)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMRaw(
|
||||
JNIEnv* env, jclass, jint id, jshort value) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMRaw((HAL_DigitalHandle)id, value, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMSpeed
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMSpeed(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMSpeed((HAL_DigitalHandle)id, value, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMPosition
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMPosition(
|
||||
JNIEnv* env, jclass, jint id, jdouble value) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMPosition((HAL_DigitalHandle)id, value, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: getPWMRaw
|
||||
* Signature: (I)S
|
||||
*/
|
||||
JNIEXPORT jshort JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMRaw(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jshort returnValue = HAL_GetPWMRaw((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: getPWMSpeed
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMSpeed(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetPWMSpeed((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: getPWMPosition
|
||||
* Signature: (I)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMPosition(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
jdouble returnValue = HAL_GetPWMPosition((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMDisabled
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMDisabled(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMDisabled((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: latchPWMZero
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_latchPWMZero(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
int32_t status = 0;
|
||||
HAL_LatchPWMZero((HAL_DigitalHandle)id, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PWMJNI
|
||||
* Method: setPWMPeriodScale
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMPeriodScale(
|
||||
JNIEnv* env, jclass, jint id, jint value) {
|
||||
PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
|
||||
PWMJNI_LOG(logDEBUG) << "PeriodScale Value = " << value;
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMPeriodScale((HAL_DigitalHandle)id, value, &status);
|
||||
PWMJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
297
hal/src/main/native/cpp/jni/PortsJNI.cpp
Normal file
297
hal/src/main/native/cpp/jni/PortsJNI.cpp
Normal file
@@ -0,0 +1,297 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_PortsJNI.h"
|
||||
|
||||
#include "HAL/Ports.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel portsJNILogLevel = logWARNING;
|
||||
|
||||
#define PORTSJNI_LOG(level) \
|
||||
if (level > portsJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumAccumulators
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumAccumulators(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAccumulators";
|
||||
jint value = HAL_GetNumAccumulators();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumAnalogTriggers
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumAnalogTriggers(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogTriggers";
|
||||
jint value = HAL_GetNumAnalogTriggers();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumAnalogInputs
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumAnalogInputs(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogInputs";
|
||||
jint value = HAL_GetNumAnalogInputs();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumAnalogOutputs
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumAnalogOutputs(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogOutputs";
|
||||
jint value = HAL_GetNumAnalogOutputs();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumCounters
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumCounters(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumCounters";
|
||||
jint value = HAL_GetNumCounters();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumDigitalHeaders
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumDigitalHeaders(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalHeaders";
|
||||
jint value = HAL_GetNumDigitalHeaders();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumPWMHeaders
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumPWMHeaders(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPWMHeaders";
|
||||
jint value = HAL_GetNumPWMHeaders();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumDigitalChannels
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumDigitalChannels(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalChannels";
|
||||
jint value = HAL_GetNumDigitalChannels();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumPWMChannels
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumPWMChannels(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPWMChannels";
|
||||
jint value = HAL_GetNumPWMChannels();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumDigitalPWMOutputs
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumDigitalPWMOutputs(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalPWMOutputs";
|
||||
jint value = HAL_GetNumDigitalPWMOutputs();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumEncoders
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumEncoders(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumEncoders";
|
||||
jint value = HAL_GetNumEncoders();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumInterrupts
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumInterrupts(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumInterrupts";
|
||||
jint value = HAL_GetNumInterrupts();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumRelayChannels
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumRelayChannels(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumRelayChannels";
|
||||
jint value = HAL_GetNumRelayChannels();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumRelayHeaders
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumRelayHeaders(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumRelayHeaders";
|
||||
jint value = HAL_GetNumRelayHeaders();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumPCMModules
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumPCMModules(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPCMModules";
|
||||
jint value = HAL_GetNumPCMModules();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumSolenoidChannels
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumSolenoidChannels(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumSolenoidChannels";
|
||||
jint value = HAL_GetNumSolenoidChannels();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumPDPModules
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumPDPModules(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPDPModules";
|
||||
jint value = HAL_GetNumPDPModules();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PortsJNI
|
||||
* Method: getNumPDPChannels
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PortsJNI_getNumPDPChannels(
|
||||
JNIEnv *env, jclass) {
|
||||
PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPDPChannels";
|
||||
jint value = HAL_GetNumPDPChannels();
|
||||
PORTSJNI_LOG(logDEBUG) << "Value = " << value;
|
||||
return value;
|
||||
}
|
||||
}
|
||||
202
hal/src/main/native/cpp/jni/PowerJNI.cpp
Normal file
202
hal/src/main/native/cpp/jni/PowerJNI.cpp
Normal file
@@ -0,0 +1,202 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "HAL/Power.h"
|
||||
#include <jni.h>
|
||||
#include "HALUtil.h"
|
||||
#include "edu_wpi_first_wpilibj_hal_PowerJNI.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getVinVoltage
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinVoltage(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetVinVoltage(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getVinCurrent
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinCurrent(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetVinCurrent(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserVoltage6V
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage6V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserVoltage6V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrent6V
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent6V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserCurrent6V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserActive6V
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserActive6V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetUserActive6V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrentFaults6V
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults6V(
|
||||
JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
int32_t val = HAL_GetUserCurrentFaults6V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserVoltage5V
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage5V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserVoltage5V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrent5V
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent5V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserCurrent5V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserActive5V
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserActive5V(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetUserActive5V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrentFaults5V
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults5V(
|
||||
JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
int32_t val = HAL_GetUserCurrentFaults5V(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserVoltage3V3
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage3V3(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserVoltage3V3(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrent3V3
|
||||
* Signature: ()D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent3V3(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
double val = HAL_GetUserCurrent3V3(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserActive3V3
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserActive3V3(JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetUserActive3V3(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_PowerJNI
|
||||
* Method: getUserCurrentFaults3V3
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults3V3(
|
||||
JNIEnv* env, jclass) {
|
||||
int32_t status = 0;
|
||||
int32_t val = HAL_GetUserCurrentFaults3V3(&status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
109
hal/src/main/native/cpp/jni/RelayJNI.cpp
Normal file
109
hal/src/main/native/cpp/jni/RelayJNI.cpp
Normal file
@@ -0,0 +1,109 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_RelayJNI.h"
|
||||
|
||||
#include "HAL/Relay.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HALUtil.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel relayJNILogLevel = logWARNING;
|
||||
|
||||
#define RELAYJNI_LOG(level) \
|
||||
if (level > relayJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_RelayJNI
|
||||
* Method: initializeRelayPort
|
||||
* Signature: (IZ)I;
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_RelayJNI_initializeRelayPort(
|
||||
JNIEnv* env, jclass, jint id, jboolean fwd) {
|
||||
RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI initializeRelayPort";
|
||||
RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
RELAYJNI_LOG(logDEBUG) << "Forward = " << (jint)fwd;
|
||||
int32_t status = 0;
|
||||
HAL_RelayHandle handle = HAL_InitializeRelayPort((HAL_PortHandle)id, (uint8_t) fwd, &status);
|
||||
RELAYJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
RELAYJNI_LOG(logDEBUG) << "Relay Handle = " << handle;
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumRelayChannels(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jint) handle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_RelayJNI
|
||||
* Method: freeRelayPort
|
||||
* Signature: (I)V;
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_RelayJNI_freeRelayPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI freeRelayPort";
|
||||
RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
|
||||
HAL_FreeRelayPort((HAL_RelayHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_RelayJNI
|
||||
* Method: checkRelayChannel
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_RelayJNI_checkRelayChannel(
|
||||
JNIEnv *env, jclass, jint channel) {
|
||||
RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI checkRelayChannel";
|
||||
RELAYJNI_LOG(logDEBUG) << "Channel = " << channel;
|
||||
return (jboolean)HAL_CheckRelayChannel((uint8_t) channel);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_RelayJNI
|
||||
* Method: setRelay
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_RelayJNI_setRelay(
|
||||
JNIEnv* env, jclass, jint id, jboolean value) {
|
||||
RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI setRelay";
|
||||
RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
|
||||
RELAYJNI_LOG(logDEBUG) << "Flag = " << (jint)value;
|
||||
int32_t status = 0;
|
||||
HAL_SetRelay((HAL_RelayHandle)id, value, &status);
|
||||
RELAYJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_RelayJNI
|
||||
* Method: getRelay
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_RelayJNI_getRelay(
|
||||
JNIEnv* env, jclass, jint id) {
|
||||
RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI getRelay";
|
||||
RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
|
||||
int32_t status = 0;
|
||||
jboolean returnValue = HAL_GetRelay((HAL_RelayHandle)id, &status);
|
||||
RELAYJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
RELAYJNI_LOG(logDEBUG) << "getRelayResult = " << (jint)returnValue;
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
438
hal/src/main/native/cpp/jni/SPIJNI.cpp
Normal file
438
hal/src/main/native/cpp/jni/SPIJNI.cpp
Normal file
@@ -0,0 +1,438 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_SPIJNI.h"
|
||||
|
||||
#include "HAL/SPI.h"
|
||||
#include "HALUtil.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel spiJNILogLevel = logWARNING;
|
||||
|
||||
#define SPIJNI_LOG(level) \
|
||||
if (level > spiJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiInitialize
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiInitialize(
|
||||
JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiInitialize";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
int32_t status = 0;
|
||||
HAL_InitializeSPI(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatusForceThrow(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiTransaction
|
||||
* Signature: (ILjava/nio/ByteBuffer;Ljava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiTransaction(
|
||||
JNIEnv *env, jclass, jint port, jobject dataToSend, jobject dataReceived,
|
||||
jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiTransaction";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
uint8_t *dataToSendPtr = nullptr;
|
||||
if (dataToSend != 0) {
|
||||
dataToSendPtr = (uint8_t *)env->GetDirectBufferAddress(dataToSend);
|
||||
}
|
||||
uint8_t *dataReceivedPtr =
|
||||
(uint8_t *)env->GetDirectBufferAddress(dataReceived);
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
SPIJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
|
||||
SPIJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
|
||||
jint retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), dataToSendPtr, dataReceivedPtr, size);
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiTransactionB
|
||||
* Signature: (I[B[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiTransactionB(
|
||||
JNIEnv *env, jclass, jint port, jbyteArray dataToSend, jbyteArray dataReceived,
|
||||
jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiTransactionB";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
llvm::SmallVector<uint8_t, 128> recvBuf;
|
||||
recvBuf.resize(size);
|
||||
jint retVal =
|
||||
HAL_TransactionSPI(static_cast<HAL_SPIPort>(port),
|
||||
reinterpret_cast<const uint8_t *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
recvBuf.data(), size);
|
||||
env->SetByteArrayRegion(dataReceived, 0, size,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiWrite
|
||||
* Signature: (ILjava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiWrite(
|
||||
JNIEnv *env, jclass, jint port, jobject dataToSend, jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiWrite";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
uint8_t *dataToSendPtr = nullptr;
|
||||
if (dataToSend != 0) {
|
||||
dataToSendPtr = (uint8_t *)env->GetDirectBufferAddress(dataToSend);
|
||||
}
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
SPIJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
|
||||
jint retVal = HAL_WriteSPI(static_cast<HAL_SPIPort>(port), dataToSendPtr, size);
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiWriteB
|
||||
* Signature: (I[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiWriteB(
|
||||
JNIEnv *env, jclass, jint port, jbyteArray dataToSend, jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiWriteB";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
jint retVal = HAL_WriteSPI(static_cast<HAL_SPIPort>(port),
|
||||
reinterpret_cast<const uint8_t *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
size);
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiRead
|
||||
* Signature: (IZLjava/nio/ByteBuffer;B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiRead(
|
||||
JNIEnv *env, jclass, jint port, jboolean initiate, jobject dataReceived, jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiRead";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "Initiate = " << (jboolean)initiate;
|
||||
uint8_t *dataReceivedPtr =
|
||||
(uint8_t *)env->GetDirectBufferAddress(dataReceived);
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
SPIJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
|
||||
jint retVal;
|
||||
if (initiate) {
|
||||
llvm::SmallVector<uint8_t, 128> sendBuf;
|
||||
sendBuf.resize(size);
|
||||
retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(), dataReceivedPtr, size);
|
||||
} else {
|
||||
retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port), (uint8_t *)dataReceivedPtr, size);
|
||||
}
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiReadB
|
||||
* Signature: (IZ[BB)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiReadB(
|
||||
JNIEnv *env, jclass, jint port, jboolean initiate, jbyteArray dataReceived, jbyte size) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadB";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "Initiate = " << (jboolean)initiate;
|
||||
SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
|
||||
jint retVal;
|
||||
llvm::SmallVector<uint8_t, 128> recvBuf;
|
||||
recvBuf.resize(size);
|
||||
if (initiate) {
|
||||
llvm::SmallVector<uint8_t, 128> sendBuf;
|
||||
sendBuf.resize(size);
|
||||
retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(), recvBuf.data(), size);
|
||||
} else {
|
||||
retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port), recvBuf.data(), size);
|
||||
}
|
||||
env->SetByteArrayRegion(dataReceived, 0, size,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiClose
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiClose(JNIEnv *, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiClose";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
HAL_CloseSPI(static_cast<HAL_SPIPort>(port));
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiSetSpeed
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiSetSpeed(
|
||||
JNIEnv *, jclass, jint port, jint speed) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetSpeed";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "Speed = " << (jint)speed;
|
||||
HAL_SetSPISpeed(static_cast<HAL_SPIPort>(port), speed);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiSetOpts
|
||||
* Signature: (IIII)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiSetOpts(
|
||||
JNIEnv *, jclass, jint port, jint msb_first, jint sample_on_trailing,
|
||||
jint clk_idle_high) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetOpts";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
SPIJNI_LOG(logDEBUG) << "msb_first = " << msb_first;
|
||||
SPIJNI_LOG(logDEBUG) << "sample_on_trailing = " << sample_on_trailing;
|
||||
SPIJNI_LOG(logDEBUG) << "clk_idle_high = " << clk_idle_high;
|
||||
HAL_SetSPIOpts(static_cast<HAL_SPIPort>(port), msb_first, sample_on_trailing, clk_idle_high);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiSetChipSelectActiveHigh
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiSetChipSelectActiveHigh(
|
||||
JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetCSActiveHigh";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
int32_t status = 0;
|
||||
HAL_SetSPIChipSelectActiveHigh(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiSetChipSelectActiveLow
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiSetChipSelectActiveLow(
|
||||
JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetCSActiveLow";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
int32_t status = 0;
|
||||
HAL_SetSPIChipSelectActiveLow(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiInitAuto
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiInitAuto
|
||||
(JNIEnv *env, jclass, jint port, jint bufferSize) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiInitAuto";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "BufferSize = " << bufferSize;
|
||||
int32_t status = 0;
|
||||
HAL_InitSPIAuto(static_cast<HAL_SPIPort>(port), bufferSize, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiFreeAuto
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiFreeAuto
|
||||
(JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiFreeAuto";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
int32_t status = 0;
|
||||
HAL_FreeSPIAuto(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiStartAutoRate
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiStartAutoRate
|
||||
(JNIEnv *env, jclass, jint port, jdouble period) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStartAutoRate";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "Period = " << period;
|
||||
int32_t status = 0;
|
||||
HAL_StartSPIAutoRate(static_cast<HAL_SPIPort>(port), period, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiStartAutoTrigger
|
||||
* Signature: (IIIZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiStartAutoTrigger
|
||||
(JNIEnv *env, jclass, jint port, jint digitalSourceHandle, jint analogTriggerType, jboolean triggerRising, jboolean triggerFalling) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStartAutoTrigger";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "DigitalSourceHandle = " << digitalSourceHandle;
|
||||
SPIJNI_LOG(logDEBUG) << "AnalogTriggerType = " << analogTriggerType;
|
||||
SPIJNI_LOG(logDEBUG) << "TriggerRising = " << (jint)triggerRising;
|
||||
SPIJNI_LOG(logDEBUG) << "TriggerFalling = " << (jint)triggerFalling;
|
||||
int32_t status = 0;
|
||||
HAL_StartSPIAutoTrigger(static_cast<HAL_SPIPort>(port), digitalSourceHandle,
|
||||
static_cast<HAL_AnalogTriggerType>(analogTriggerType), triggerRising,
|
||||
triggerFalling, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiStopAuto
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiStopAuto
|
||||
(JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStopAuto";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
int32_t status = 0;
|
||||
HAL_StopSPIAuto(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiSetAutoTransmitData
|
||||
* Signature: (I[BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiSetAutoTransmitData
|
||||
(JNIEnv *env, jclass, jint port, jbyteArray dataToSend, jint zeroSize) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetAutoTransmitData";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "ZeroSize = " << zeroSize;
|
||||
JByteArrayRef jarr(env, dataToSend);
|
||||
int32_t status = 0;
|
||||
HAL_SetSPIAutoTransmitData(static_cast<HAL_SPIPort>(port),
|
||||
reinterpret_cast<const uint8_t*>(jarr.array().data()),
|
||||
jarr.array().size(), zeroSize, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiForceAutoRead
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiForceAutoRead
|
||||
(JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiForceAutoRead";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
int32_t status = 0;
|
||||
HAL_ForceSPIAutoRead(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiReadAutoReceivedData
|
||||
* Signature: (ILjava/nio/ByteBuffer;ID)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiReadAutoReceivedData__ILjava_nio_ByteBuffer_2ID
|
||||
(JNIEnv *env, jclass, jint port, jobject buffer, jint numToRead, jdouble timeout) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadAutoReceivedData";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "NumToRead = " << numToRead;
|
||||
SPIJNI_LOG(logDEBUG) << "Timeout = " << timeout;
|
||||
uint8_t *recvBuf = (uint8_t *)env->GetDirectBufferAddress(buffer);
|
||||
int32_t status = 0;
|
||||
jint retval = HAL_ReadSPIAutoReceivedData(static_cast<HAL_SPIPort>(port), recvBuf, numToRead, timeout, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
SPIJNI_LOG(logDEBUG) << "Return = " << retval;
|
||||
CheckStatus(env, status);
|
||||
return retval;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiReadAutoReceivedData
|
||||
* Signature: (I[BID)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiReadAutoReceivedData__I_3BID
|
||||
(JNIEnv *env, jclass, jint port, jbyteArray buffer, jint numToRead, jdouble timeout) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadAutoReceivedData";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
SPIJNI_LOG(logDEBUG) << "NumToRead = " << numToRead;
|
||||
SPIJNI_LOG(logDEBUG) << "Timeout = " << timeout;
|
||||
llvm::SmallVector<uint8_t, 128> recvBuf;
|
||||
recvBuf.resize(numToRead);
|
||||
int32_t status = 0;
|
||||
jint retval = HAL_ReadSPIAutoReceivedData(static_cast<HAL_SPIPort>(port), recvBuf.data(), numToRead, timeout, &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
SPIJNI_LOG(logDEBUG) << "Return = " << retval;
|
||||
if (!CheckStatus(env, status)) return retval;
|
||||
if (numToRead > 0) {
|
||||
env->SetByteArrayRegion(buffer, 0, numToRead,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SPIJNI
|
||||
* Method: spiGetAutoDroppedCount
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SPIJNI_spiGetAutoDroppedCount
|
||||
(JNIEnv *env, jclass, jint port) {
|
||||
SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiGetAutoDroppedCount";
|
||||
SPIJNI_LOG(logDEBUG) << "Port = " << port;
|
||||
int32_t status = 0;
|
||||
auto retval = HAL_GetSPIAutoDroppedCount(static_cast<HAL_SPIPort>(port), &status);
|
||||
SPIJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
SPIJNI_LOG(logDEBUG) << "Return = " << retval;
|
||||
CheckStatus(env, status);
|
||||
return retval;
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
341
hal/src/main/native/cpp/jni/SerialPortJNI.cpp
Normal file
341
hal/src/main/native/cpp/jni/SerialPortJNI.cpp
Normal file
@@ -0,0 +1,341 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_SerialPortJNI.h"
|
||||
|
||||
#include "HAL/SerialPort.h"
|
||||
#include "HALUtil.h"
|
||||
#include "support/jni_util.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel serialJNILogLevel = logWARNING;
|
||||
|
||||
#define SERIALJNI_LOG(level) \
|
||||
if (level > serialJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialInitializePort
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialInitializePort(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize";
|
||||
SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
int32_t status = 0;
|
||||
HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatusForceThrow(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialInitializePortDirect
|
||||
* Signature: (BLjava/lang/String;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialInitializePortDirect(
|
||||
JNIEnv* env, jclass, jbyte port, jstring portName) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize Direct";
|
||||
SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
|
||||
JStringRef portNameRef{env, portName};
|
||||
SERIALJNI_LOG(logDEBUG) << "PortName = " << portNameRef.c_str();
|
||||
int32_t status = 0;
|
||||
HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port),
|
||||
portNameRef.c_str(), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatusForceThrow(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetBaudRate
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetBaudRate(
|
||||
JNIEnv* env, jclass, jbyte port, jint rate) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Baud Rate";
|
||||
SERIALJNI_LOG(logDEBUG) << "Baud: " << rate;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), rate, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetDataBits
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetDataBits(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte bits) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Data Bits";
|
||||
SERIALJNI_LOG(logDEBUG) << "Data Bits: " << bits;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), bits, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetParity
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetParity(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte parity) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Parity";
|
||||
SERIALJNI_LOG(logDEBUG) << "Parity: " << parity;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetStopBits
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetStopBits(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte bits) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Stop Bits";
|
||||
SERIALJNI_LOG(logDEBUG) << "Stop Bits: " << bits;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), bits, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetWriteMode
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetWriteMode(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte mode) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Mode";
|
||||
SERIALJNI_LOG(logDEBUG) << "Write mode: " << mode;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialWriteMode(static_cast<HAL_SerialPort>(port), mode, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetFlowControl
|
||||
* Signature: (BB)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetFlowControl(
|
||||
JNIEnv* env, jclass, jbyte port, jbyte flow) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Flow Control";
|
||||
SERIALJNI_LOG(logDEBUG) << "Flow Control: " << flow;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialFlowControl(static_cast<HAL_SerialPort>(port), flow, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetTimeout
|
||||
* Signature: (BD)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetTimeout(
|
||||
JNIEnv* env, jclass, jbyte port, jdouble timeout) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Timeout";
|
||||
SERIALJNI_LOG(logDEBUG) << "Timeout: " << timeout;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialTimeout(static_cast<HAL_SerialPort>(port), timeout, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialEnableTermination
|
||||
* Signature: (BC)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialEnableTermination(
|
||||
JNIEnv* env, jclass, jbyte port, jchar terminator) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Enable Termination";
|
||||
SERIALJNI_LOG(logDEBUG) << "Terminator: " << terminator;
|
||||
int32_t status = 0;
|
||||
HAL_EnableSerialTermination(static_cast<HAL_SerialPort>(port), terminator, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialDisableTermination
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialDisableTermination(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Disable termination";
|
||||
int32_t status = 0;
|
||||
HAL_DisableSerialTermination(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetReadBufferSize
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetReadBufferSize(
|
||||
JNIEnv* env, jclass, jbyte port, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Read Buffer Size";
|
||||
SERIALJNI_LOG(logDEBUG) << "Size: " << size;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPort>(port), size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialSetWriteBufferSize
|
||||
* Signature: (BI)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetWriteBufferSize(
|
||||
JNIEnv* env, jclass, jbyte port, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Buffer Size";
|
||||
SERIALJNI_LOG(logDEBUG) << "Size: " << size;
|
||||
int32_t status = 0;
|
||||
HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPort>(port), size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialGetBytesReceived
|
||||
* Signature: (B)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialGetBytesReceived(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Get Bytes Received";
|
||||
int32_t status = 0;
|
||||
jint retVal = HAL_GetSerialBytesReceived(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialRead
|
||||
* Signature: (B[BI)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialRead(
|
||||
JNIEnv* env, jclass, jbyte port, jbyteArray dataReceived, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Read";
|
||||
llvm::SmallVector<char, 128> recvBuf;
|
||||
recvBuf.resize(size);
|
||||
int32_t status = 0;
|
||||
jint retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(port), recvBuf.data(),
|
||||
size, &status);
|
||||
env->SetByteArrayRegion(dataReceived, 0, size,
|
||||
reinterpret_cast<const jbyte *>(recvBuf.data()));
|
||||
SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialWrite
|
||||
* Signature: (B[BI)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialWrite(
|
||||
JNIEnv* env, jclass, jbyte port, jbyteArray dataToSend, jint size) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Write";
|
||||
int32_t status = 0;
|
||||
jint retVal =
|
||||
HAL_WriteSerial(static_cast<HAL_SerialPort>(port),
|
||||
reinterpret_cast<const char *>(
|
||||
JByteArrayRef(env, dataToSend).array().data()),
|
||||
size, &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialFlush
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialFlush(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Flush";
|
||||
int32_t status = 0;
|
||||
HAL_FlushSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialClear
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialClear(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Clear";
|
||||
int32_t status = 0;
|
||||
HAL_ClearSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
|
||||
* Method: serialClose
|
||||
* Signature: (B)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialClose(
|
||||
JNIEnv* env, jclass, jbyte port) {
|
||||
SERIALJNI_LOG(logDEBUG) << "Serial Close";
|
||||
int32_t status = 0;
|
||||
HAL_CloseSerial(static_cast<HAL_SerialPort>(port), &status);
|
||||
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
226
hal/src/main/native/cpp/jni/SolenoidJNI.cpp
Normal file
226
hal/src/main/native/cpp/jni/SolenoidJNI.cpp
Normal file
@@ -0,0 +1,226 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <jni.h>
|
||||
#include "HAL/Solenoid.h"
|
||||
#include "HAL/Ports.h"
|
||||
#include "HAL/handles/HandlesInternal.h"
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_SolenoidJNI.h"
|
||||
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
TLogLevel solenoidJNILogLevel = logERROR;
|
||||
|
||||
#define SOLENOIDJNI_LOG(level) \
|
||||
if (level > solenoidJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: initializeSolenoidPort
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_initializeSolenoidPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI initializeSolenoidPort";
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_SolenoidHandle handle =
|
||||
HAL_InitializeSolenoidPort((HAL_PortHandle)id, &status);
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Status = " << status;
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Solenoid Port Handle = " << handle;
|
||||
|
||||
// Use solenoid channels, as we have to pick one.
|
||||
CheckStatusRange(env, status, 0, HAL_GetNumSolenoidChannels(),
|
||||
hal::getPortHandleChannel((HAL_PortHandle)id));
|
||||
return (jint)handle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: checkSolenoidChannel
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_checkSolenoidChannel(
|
||||
JNIEnv *env, jclass, jint channel) {
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI checkSolenoidChannel";
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Channel = " << channel;
|
||||
return HAL_CheckSolenoidChannel(channel);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: checkSolenoidModule
|
||||
* Signature: (I)Z;
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_checkSolenoidModule(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI checkSolenoidModule";
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Module = " << module;
|
||||
return HAL_CheckSolenoidModule(module);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: freeSolenoidPort
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_freeSolenoidPort(
|
||||
JNIEnv *env, jclass, jint id) {
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI initializeSolenoidPort";
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_SolenoidHandle)id;
|
||||
HAL_FreeSolenoidPort((HAL_SolenoidHandle)id);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: setSolenoid
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_setSolenoid(
|
||||
JNIEnv *env, jclass, jint solenoid_port, jboolean value) {
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI SetSolenoid";
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Solenoid Port Handle = "
|
||||
<< (HAL_SolenoidHandle)solenoid_port;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_SetSolenoid((HAL_SolenoidHandle)solenoid_port, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: getSolenoid
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_getSolenoid(
|
||||
JNIEnv *env, jclass, jint solenoid_port) {
|
||||
int32_t status = 0;
|
||||
jboolean val = HAL_GetSolenoid((HAL_SolenoidHandle)solenoid_port, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: getAllSolenoids
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_getAllSolenoids(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
jint val = HAL_GetAllSolenoids(module, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: getPCMSolenoidBlackList
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_getPCMSolenoidBlackList(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
jint val = HAL_GetPCMSolenoidBlackList(module, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: getPCMSolenoidVoltageStickyFault
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_getPCMSolenoidVoltageStickyFault(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: getPCMSolenoidVoltageFault
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_getPCMSolenoidVoltageFault(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
bool val = HAL_GetPCMSolenoidVoltageFault(module, &status);
|
||||
CheckStatus(env, status);
|
||||
return val;
|
||||
}
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: clearAllPCMStickyFaults
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_clearAllPCMStickyFaults(
|
||||
JNIEnv *env, jclass, jint module) {
|
||||
int32_t status = 0;
|
||||
HAL_ClearAllPCMStickyFaults(module, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: setOneShotDuration
|
||||
* Signature: (IJ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_setOneShotDuration
|
||||
(JNIEnv *env, jclass, jint solenoid_port, jlong durationMS)
|
||||
{
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI SetOneShotDuration";
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Solenoid Port Handle = "
|
||||
<< (HAL_SolenoidHandle)solenoid_port;
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Duration (MS) = " << durationMS;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_SetOneShotDuration((HAL_SolenoidHandle)solenoid_port, durationMS, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_SolenoidJNI
|
||||
* Method: fireOneShot
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SolenoidJNI_fireOneShot
|
||||
(JNIEnv *env, jclass, jint solenoid_port)
|
||||
{
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI fireOneShot";
|
||||
|
||||
SOLENOIDJNI_LOG(logDEBUG) << "Solenoid Port Handle = "
|
||||
<< (HAL_SolenoidHandle)solenoid_port;
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_FireOneShot((HAL_SolenoidHandle)solenoid_port, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
} // extern "C"
|
||||
73
hal/src/main/native/cpp/jni/ThreadsJNI.cpp
Normal file
73
hal/src/main/native/cpp/jni/ThreadsJNI.cpp
Normal file
@@ -0,0 +1,73 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2016. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <jni.h>
|
||||
#include "HAL/cpp/Log.h"
|
||||
|
||||
#include "edu_wpi_first_wpilibj_hal_ThreadsJNI.h"
|
||||
|
||||
#include "HAL/Threads.h"
|
||||
#include "HALUtil.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// set the logging level
|
||||
TLogLevel threadsJNILogLevel = logWARNING;
|
||||
|
||||
#define THREADSJNI_LOG(level) \
|
||||
if (level > threadsJNILogLevel) \
|
||||
; \
|
||||
else \
|
||||
Log().Get(level)
|
||||
|
||||
extern "C" {
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_ThreadsJNI
|
||||
* Method: GetCurrentThreadPriority
|
||||
* Signature: ()I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_ThreadsJNI_getCurrentThreadPriority
|
||||
(JNIEnv *env, jclass) {
|
||||
THREADSJNI_LOG(logDEBUG) << "Callling GetCurrentThreadPriority";
|
||||
int32_t status = 0;
|
||||
HAL_Bool isRT = false;
|
||||
auto ret = HAL_GetCurrentThreadPriority(&isRT, &status);
|
||||
CheckStatus(env, status);
|
||||
return (jint)ret;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_ThreadsJNI
|
||||
* Method: GetCurrentThreadIsRealTime
|
||||
* Signature: ()Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_ThreadsJNI_getCurrentThreadIsRealTime
|
||||
(JNIEnv *env, jclass) {
|
||||
THREADSJNI_LOG(logDEBUG) << "Callling GetCurrentThreadIsRealTime";
|
||||
int32_t status = 0;
|
||||
HAL_Bool isRT = false;
|
||||
HAL_GetCurrentThreadPriority(&isRT, &status);
|
||||
CheckStatus(env, status);
|
||||
return (jboolean)isRT;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_wpilibj_hal_ThreadsJNI
|
||||
* Method: SetCurrentThreadPriority
|
||||
* Signature: (ZI)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL Java_edu_wpi_first_wpilibj_hal_ThreadsJNI_setCurrentThreadPriority
|
||||
(JNIEnv *env, jclass, jboolean realTime, jint priority) {
|
||||
THREADSJNI_LOG(logDEBUG) << "Callling SetCurrentThreadPriority";
|
||||
int32_t status = 0;
|
||||
auto ret = HAL_SetCurrentThreadPriority((HAL_Bool)realTime, (int32_t)priority, &status);
|
||||
CheckStatus(env, status);
|
||||
return (jboolean)ret;
|
||||
}
|
||||
|
||||
}
|
||||
Reference in New Issue
Block a user