mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal, wpilib] Remove analog accumulator and analog gyro (#7697)
The 2 high level classes were temporarily kept to keep the examples compiling. We will remove those when we have the interface into the built in IMU.
This commit is contained in:
@@ -1,143 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/AnalogGyro.h"
|
||||
|
||||
#include <climits>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include <hal/AnalogGyro.h>
|
||||
#include <hal/Errors.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
#include "frc/AnalogInput.h"
|
||||
#include "frc/Errors.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
AnalogGyro::AnalogGyro(int channel)
|
||||
: AnalogGyro(std::make_shared<AnalogInput>(channel)) {
|
||||
wpi::SendableRegistry::AddChild(this, m_analog.get());
|
||||
}
|
||||
|
||||
AnalogGyro::AnalogGyro(AnalogInput* channel)
|
||||
: AnalogGyro(std::shared_ptr<AnalogInput>(
|
||||
channel, wpi::NullDeleter<AnalogInput>())) {}
|
||||
|
||||
AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
|
||||
: m_analog(channel) {
|
||||
if (!channel) {
|
||||
throw FRC_MakeError(err::NullParameter, "channel");
|
||||
}
|
||||
InitGyro();
|
||||
Calibrate();
|
||||
}
|
||||
|
||||
AnalogGyro::AnalogGyro(int channel, int center, double offset)
|
||||
: AnalogGyro(std::make_shared<AnalogInput>(channel), center, offset) {
|
||||
wpi::SendableRegistry::AddChild(this, m_analog.get());
|
||||
}
|
||||
|
||||
AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
|
||||
double offset)
|
||||
: m_analog(channel) {
|
||||
if (!channel) {
|
||||
throw FRC_MakeError(err::NullParameter, "channel");
|
||||
}
|
||||
InitGyro();
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
|
||||
offset, center, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
Reset();
|
||||
}
|
||||
|
||||
double AnalogGyro::GetAngle() const {
|
||||
int32_t status = 0;
|
||||
double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
return value;
|
||||
}
|
||||
|
||||
double AnalogGyro::GetRate() const {
|
||||
int32_t status = 0;
|
||||
double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
return value;
|
||||
}
|
||||
|
||||
int AnalogGyro::GetCenter() const {
|
||||
int32_t status = 0;
|
||||
int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
return value;
|
||||
}
|
||||
|
||||
double AnalogGyro::GetOffset() const {
|
||||
int32_t status = 0;
|
||||
double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
return value;
|
||||
}
|
||||
|
||||
void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
|
||||
voltsPerDegreePerSecond, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
void AnalogGyro::SetDeadband(double volts) {
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
void AnalogGyro::Reset() {
|
||||
int32_t status = 0;
|
||||
HAL_ResetAnalogGyro(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
void AnalogGyro::InitGyro() {
|
||||
if (m_gyroHandle == HAL_kInvalidHandle) {
|
||||
int32_t status = 0;
|
||||
std::string stackTrace = wpi::GetStackTrace(1);
|
||||
m_gyroHandle =
|
||||
HAL_InitializeAnalogGyro(m_analog->m_port, stackTrace.c_str(), &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
int32_t status = 0;
|
||||
HAL_SetupAnalogGyro(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel() + 1);
|
||||
|
||||
wpi::SendableRegistry::AddLW(this, "AnalogGyro", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
void AnalogGyro::Calibrate() {
|
||||
int32_t status = 0;
|
||||
HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_analog->GetChannel());
|
||||
}
|
||||
|
||||
Rotation2d AnalogGyro::GetRotation2d() const {
|
||||
return units::degree_t{-GetAngle()};
|
||||
}
|
||||
|
||||
std::shared_ptr<AnalogInput> AnalogGyro::GetAnalogInput() const {
|
||||
return m_analog;
|
||||
}
|
||||
|
||||
void AnalogGyro::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Gyro");
|
||||
builder.AddDoubleProperty("Value", [=, this] { return GetAngle(); }, nullptr);
|
||||
}
|
||||
@@ -6,7 +6,6 @@
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <hal/AnalogAccumulator.h>
|
||||
#include <hal/AnalogInput.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
@@ -111,70 +110,6 @@ int AnalogInput::GetOffset() const {
|
||||
return offset;
|
||||
}
|
||||
|
||||
bool AnalogInput::IsAccumulatorChannel() const {
|
||||
int32_t status = 0;
|
||||
bool isAccum = HAL_IsAccumulatorChannel(m_port, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
return isAccum;
|
||||
}
|
||||
|
||||
void AnalogInput::InitAccumulator() {
|
||||
m_accumulatorOffset = 0;
|
||||
int32_t status = 0;
|
||||
HAL_InitAccumulator(m_port, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
}
|
||||
|
||||
void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
|
||||
m_accumulatorOffset = initialValue;
|
||||
}
|
||||
|
||||
void AnalogInput::ResetAccumulator() {
|
||||
int32_t status = 0;
|
||||
HAL_ResetAccumulator(m_port, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
|
||||
// Wait until the next sample, so the next call to GetAccumulator*()
|
||||
// won't have old values.
|
||||
const double sampleTime = 1.0 / GetSampleRate();
|
||||
const double overSamples = 1 << GetOversampleBits();
|
||||
const double averageSamples = 1 << GetAverageBits();
|
||||
Wait(units::second_t{sampleTime * overSamples * averageSamples});
|
||||
}
|
||||
|
||||
void AnalogInput::SetAccumulatorCenter(int center) {
|
||||
int32_t status = 0;
|
||||
HAL_SetAccumulatorCenter(m_port, center, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
}
|
||||
|
||||
void AnalogInput::SetAccumulatorDeadband(int deadband) {
|
||||
int32_t status = 0;
|
||||
HAL_SetAccumulatorDeadband(m_port, deadband, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
}
|
||||
|
||||
int64_t AnalogInput::GetAccumulatorValue() const {
|
||||
int32_t status = 0;
|
||||
int64_t value = HAL_GetAccumulatorValue(m_port, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
return value + m_accumulatorOffset;
|
||||
}
|
||||
|
||||
int64_t AnalogInput::GetAccumulatorCount() const {
|
||||
int32_t status = 0;
|
||||
int64_t count = HAL_GetAccumulatorCount(m_port, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
return count;
|
||||
}
|
||||
|
||||
void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
|
||||
int32_t status = 0;
|
||||
HAL_GetAccumulatorOutput(m_port, &value, &count, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
value += m_accumulatorOffset;
|
||||
}
|
||||
|
||||
void AnalogInput::SetSampleRate(double samplesPerSecond) {
|
||||
int32_t status = 0;
|
||||
HAL_SetAnalogSampleRate(samplesPerSecond, &status);
|
||||
|
||||
@@ -1,75 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/simulation/AnalogGyroSim.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <hal/simulation/AnalogGyroData.h>
|
||||
|
||||
#include "frc/AnalogGyro.h"
|
||||
#include "frc/AnalogInput.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace frc::sim;
|
||||
|
||||
AnalogGyroSim::AnalogGyroSim(const AnalogGyro& gyro)
|
||||
: m_index{gyro.GetAnalogInput()->GetChannel()} {}
|
||||
|
||||
AnalogGyroSim::AnalogGyroSim(int channel) : m_index{channel} {}
|
||||
|
||||
std::unique_ptr<CallbackStore> AnalogGyroSim::RegisterAngleCallback(
|
||||
NotifyCallback callback, bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogGyroAngleCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogGyroAngleCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
double AnalogGyroSim::GetAngle() const {
|
||||
return HALSIM_GetAnalogGyroAngle(m_index);
|
||||
}
|
||||
|
||||
void AnalogGyroSim::SetAngle(double angle) {
|
||||
HALSIM_SetAnalogGyroAngle(m_index, angle);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore> AnalogGyroSim::RegisterRateCallback(
|
||||
NotifyCallback callback, bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogGyroRateCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogGyroRateCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
double AnalogGyroSim::GetRate() const {
|
||||
return HALSIM_GetAnalogGyroRate(m_index);
|
||||
}
|
||||
|
||||
void AnalogGyroSim::SetRate(double rate) {
|
||||
HALSIM_SetAnalogGyroRate(m_index, rate);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore> AnalogGyroSim::RegisterInitializedCallback(
|
||||
NotifyCallback callback, bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogGyroInitializedCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogGyroInitializedCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
bool AnalogGyroSim::GetInitialized() const {
|
||||
return HALSIM_GetAnalogGyroInitialized(m_index);
|
||||
}
|
||||
|
||||
void AnalogGyroSim::SetInitialized(bool initialized) {
|
||||
HALSIM_SetAnalogGyroInitialized(m_index, initialized);
|
||||
}
|
||||
|
||||
void AnalogGyroSim::ResetData() {
|
||||
HALSIM_ResetAnalogGyroData(m_index);
|
||||
}
|
||||
@@ -86,95 +86,6 @@ void AnalogInputSim::SetVoltage(double voltage) {
|
||||
HALSIM_SetAnalogInVoltage(m_index, voltage);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore>
|
||||
AnalogInputSim::RegisterAccumulatorInitializedCallback(NotifyCallback callback,
|
||||
bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback,
|
||||
&HALSIM_CancelAnalogInAccumulatorInitializedCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogInAccumulatorInitializedCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
bool AnalogInputSim::GetAccumulatorInitialized() const {
|
||||
return HALSIM_GetAnalogInAccumulatorInitialized(m_index);
|
||||
}
|
||||
|
||||
void AnalogInputSim::SetAccumulatorInitialized(bool accumulatorInitialized) {
|
||||
HALSIM_SetAnalogInAccumulatorInitialized(m_index, accumulatorInitialized);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore> AnalogInputSim::RegisterAccumulatorValueCallback(
|
||||
NotifyCallback callback, bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorValueCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogInAccumulatorValueCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
int64_t AnalogInputSim::GetAccumulatorValue() const {
|
||||
return HALSIM_GetAnalogInAccumulatorValue(m_index);
|
||||
}
|
||||
|
||||
void AnalogInputSim::SetAccumulatorValue(int64_t accumulatorValue) {
|
||||
HALSIM_SetAnalogInAccumulatorValue(m_index, accumulatorValue);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore> AnalogInputSim::RegisterAccumulatorCountCallback(
|
||||
NotifyCallback callback, bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorCountCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogInAccumulatorCountCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
int64_t AnalogInputSim::GetAccumulatorCount() const {
|
||||
return HALSIM_GetAnalogInAccumulatorCount(m_index);
|
||||
}
|
||||
|
||||
void AnalogInputSim::SetAccumulatorCount(int64_t accumulatorCount) {
|
||||
HALSIM_SetAnalogInAccumulatorCount(m_index, accumulatorCount);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore>
|
||||
AnalogInputSim::RegisterAccumulatorCenterCallback(NotifyCallback callback,
|
||||
bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorCenterCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogInAccumulatorCenterCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
int AnalogInputSim::GetAccumulatorCenter() const {
|
||||
return HALSIM_GetAnalogInAccumulatorCenter(m_index);
|
||||
}
|
||||
|
||||
void AnalogInputSim::SetAccumulatorCenter(int accumulatorCenter) {
|
||||
HALSIM_SetAnalogInAccumulatorCenter(m_index, accumulatorCenter);
|
||||
}
|
||||
|
||||
std::unique_ptr<CallbackStore>
|
||||
AnalogInputSim::RegisterAccumulatorDeadbandCallback(NotifyCallback callback,
|
||||
bool initialNotify) {
|
||||
auto store = std::make_unique<CallbackStore>(
|
||||
m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorDeadbandCallback);
|
||||
store->SetUid(HALSIM_RegisterAnalogInAccumulatorDeadbandCallback(
|
||||
m_index, &CallbackStoreThunk, store.get(), initialNotify));
|
||||
return store;
|
||||
}
|
||||
|
||||
int AnalogInputSim::GetAccumulatorDeadband() const {
|
||||
return HALSIM_GetAnalogInAccumulatorDeadband(m_index);
|
||||
}
|
||||
|
||||
void AnalogInputSim::SetAccumulatorDeadband(int accumulatorDeadband) {
|
||||
HALSIM_SetAnalogInAccumulatorDeadband(m_index, accumulatorDeadband);
|
||||
}
|
||||
|
||||
void AnalogInputSim::ResetData() {
|
||||
HALSIM_ResetAnalogInData(m_index);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user