Rename our Falcons to TalonFX
This is done because both the Falcons and Krakens use a TalonFX motor
controller and our api to use them will be the same.
Signed-off-by: Maxwell Henderson <mxwhenderson@gmail.com>
Change-Id: I97249c5583e42f5ca346e754499748e555cd9f8b
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index caa8e63..2cf2109 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -492,12 +492,12 @@
)
cc_library(
- name = "falcon",
+ name = "talonfx",
srcs = [
- "falcon.cc",
+ "talonfx.cc",
],
hdrs = [
- "falcon.h",
+ "talonfx.h",
],
target_compatible_with = ["//tools/platforms/hardware:roborio"],
deps = [
@@ -523,8 +523,8 @@
],
target_compatible_with = ["//tools/platforms/hardware:roborio"],
deps = [
- ":falcon",
":loop_output_handler",
+ ":talonfx",
"//frc971:can_configuration_fbs",
"//frc971/control_loops/drivetrain:drivetrain_output_fbs",
],
@@ -540,8 +540,8 @@
],
target_compatible_with = ["//tools/platforms/hardware:roborio"],
deps = [
- ":falcon",
":loop_output_handler",
+ ":talonfx",
"//frc971:can_configuration_fbs",
],
)
@@ -553,7 +553,7 @@
target_compatible_with = ["//tools/platforms/hardware:roborio"],
visibility = ["//visibility:public"],
deps = [
- ":falcon",
+ ":talonfx",
"//aos:realtime",
"//aos/containers:sized_array",
"//aos/events:event_loop",
diff --git a/frc971/wpilib/can_drivetrain_writer.cc b/frc971/wpilib/can_drivetrain_writer.cc
index bdff308..ae82812 100644
--- a/frc971/wpilib/can_drivetrain_writer.cc
+++ b/frc971/wpilib/can_drivetrain_writer.cc
@@ -11,21 +11,21 @@
event_loop->OnRun([this]() { WriteConfigs(); });
}
-void CANDrivetrainWriter::set_falcons(
- std::vector<std::shared_ptr<Falcon>> right_falcons,
- std::vector<std::shared_ptr<Falcon>> left_falcons) {
- right_falcons_ = std::move(right_falcons);
- left_falcons_ = std::move(left_falcons);
+void CANDrivetrainWriter::set_talonfxs(
+ std::vector<std::shared_ptr<TalonFX>> right_talonfxs,
+ std::vector<std::shared_ptr<TalonFX>> left_talonfxs) {
+ right_talonfxs_ = std::move(right_talonfxs);
+ left_talonfxs_ = std::move(left_talonfxs);
}
void CANDrivetrainWriter::HandleCANConfiguration(
const CANConfiguration &configuration) {
- for (auto falcon : right_falcons_) {
- falcon->PrintConfigs();
+ for (auto talonfx : right_talonfxs_) {
+ talonfx->PrintConfigs();
}
- for (auto falcon : left_falcons_) {
- falcon->PrintConfigs();
+ for (auto talonfx : left_talonfxs_) {
+ talonfx->PrintConfigs();
}
if (configuration.reapply()) {
@@ -34,33 +34,33 @@
}
void CANDrivetrainWriter::WriteConfigs() {
- for (auto falcon : right_falcons_) {
- falcon->WriteConfigs();
+ for (auto talonfx : right_talonfxs_) {
+ talonfx->WriteConfigs();
}
- for (auto falcon : left_falcons_) {
- falcon->WriteConfigs();
+ for (auto talonfx : left_talonfxs_) {
+ talonfx->WriteConfigs();
}
}
void CANDrivetrainWriter::Write(
const ::frc971::control_loops::drivetrain::Output &output) {
- for (auto falcon : right_falcons_) {
- falcon->WriteVoltage(output.right_voltage());
+ for (auto talonfx : right_talonfxs_) {
+ talonfx->WriteVoltage(output.right_voltage());
}
- for (auto falcon : left_falcons_) {
- falcon->WriteVoltage(output.left_voltage());
+ for (auto talonfx : left_talonfxs_) {
+ talonfx->WriteVoltage(output.left_voltage());
}
}
void CANDrivetrainWriter::Stop() {
AOS_LOG(WARNING, "Drivetrain CAN output too old.\n");
- for (auto falcon : right_falcons_) {
- falcon->WriteVoltage(0);
+ for (auto talonfx : right_talonfxs_) {
+ talonfx->WriteVoltage(0);
}
- for (auto falcon : left_falcons_) {
- falcon->WriteVoltage(0);
+ for (auto talonfx : left_talonfxs_) {
+ talonfx->WriteVoltage(0);
}
}
diff --git a/frc971/wpilib/can_drivetrain_writer.h b/frc971/wpilib/can_drivetrain_writer.h
index bd396bf..1c0ba95 100644
--- a/frc971/wpilib/can_drivetrain_writer.h
+++ b/frc971/wpilib/can_drivetrain_writer.h
@@ -1,7 +1,7 @@
#include "frc971/can_configuration_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
-#include "frc971/wpilib/falcon.h"
#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/talonfx.h"
namespace frc971 {
namespace wpilib {
@@ -11,8 +11,8 @@
public:
CANDrivetrainWriter(::aos::EventLoop *event_loop);
- void set_falcons(std::vector<std::shared_ptr<Falcon>> right_falcons,
- std::vector<std::shared_ptr<Falcon>> left_falcons);
+ void set_talonfxs(std::vector<std::shared_ptr<TalonFX>> right_talonfxs,
+ std::vector<std::shared_ptr<TalonFX>> left_talonfxs);
void HandleCANConfiguration(const CANConfiguration &configuration);
@@ -26,8 +26,8 @@
void Stop() override;
- std::vector<std::shared_ptr<Falcon>> right_falcons_;
- std::vector<std::shared_ptr<Falcon>> left_falcons_;
+ std::vector<std::shared_ptr<TalonFX>> right_talonfxs_;
+ std::vector<std::shared_ptr<TalonFX>> left_talonfxs_;
};
} // namespace wpilib
diff --git a/frc971/wpilib/can_sensor_reader.cc b/frc971/wpilib/can_sensor_reader.cc
index ad244fb..54be05d 100644
--- a/frc971/wpilib/can_sensor_reader.cc
+++ b/frc971/wpilib/can_sensor_reader.cc
@@ -6,11 +6,11 @@
CANSensorReader::CANSensorReader(
aos::EventLoop *event_loop,
std::vector<ctre::phoenix6::BaseStatusSignal *> signals_registry,
- std::vector<std::shared_ptr<Falcon>> falcons,
+ std::vector<std::shared_ptr<TalonFX>> talonfxs,
std::function<void(ctre::phoenix::StatusCode status)> flatbuffer_callback)
: event_loop_(event_loop),
signals_(signals_registry.begin(), signals_registry.end()),
- falcons_(falcons),
+ talonfxs_(talonfxs),
flatbuffer_callback_(flatbuffer_callback) {
event_loop->SetRuntimeRealtimePriority(40);
@@ -32,7 +32,7 @@
ctre::phoenix6::BaseStatusSignal::WaitForAll(20_ms, signals_);
if (!status.IsOK()) {
- AOS_LOG(ERROR, "Failed to read signals from falcons: %s: %s",
+ AOS_LOG(ERROR, "Failed to read signals from talonfx motors: %s: %s",
status.GetName(), status.GetDescription());
}
diff --git a/frc971/wpilib/can_sensor_reader.h b/frc971/wpilib/can_sensor_reader.h
index 764a041..8ef5fd1 100644
--- a/frc971/wpilib/can_sensor_reader.h
+++ b/frc971/wpilib/can_sensor_reader.h
@@ -7,7 +7,7 @@
#include "aos/events/event_loop.h"
#include "aos/events/shm_event_loop.h"
#include "aos/realtime.h"
-#include "frc971/wpilib/falcon.h"
+#include "frc971/wpilib/talonfx.h"
namespace frc971 {
namespace wpilib {
@@ -16,7 +16,7 @@
CANSensorReader(
aos::EventLoop *event_loop,
std::vector<ctre::phoenix6::BaseStatusSignal *> signals_registry,
- std::vector<std::shared_ptr<Falcon>> falcons,
+ std::vector<std::shared_ptr<TalonFX>> talonfxs,
std::function<void(ctre::phoenix::StatusCode status)>
flatbuffer_callback);
@@ -27,9 +27,9 @@
const std::vector<ctre::phoenix6::BaseStatusSignal *> signals_;
- // This is a vector of falcons becuase we don't need to care
- // about falcons individually.
- std::vector<std::shared_ptr<Falcon>> falcons_;
+ // This is a vector of talonfxs becuase we don't need to care
+ // about talonfxs individually.
+ std::vector<std::shared_ptr<TalonFX>> talonfxs_;
// Pointer to the timer handler used to modify the wakeup.
::aos::TimerHandler *timer_handler_;
diff --git a/frc971/wpilib/generic_can_writer.h b/frc971/wpilib/generic_can_writer.h
index 8bacfbd..7555c0a 100644
--- a/frc971/wpilib/generic_can_writer.h
+++ b/frc971/wpilib/generic_can_writer.h
@@ -2,14 +2,14 @@
#include <string_view>
#include "frc971/can_configuration_generated.h"
-#include "frc971/wpilib/falcon.h"
#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/talonfx.h"
namespace frc971 {
namespace wpilib {
/// This class uses a callback whenever it writes so that the caller can use any
-/// flatbuffer to write to the falcon.
+/// flatbuffer to write to the talonfx motor.
template <typename T>
class GenericCANWriter : public LoopOutputHandler<T> {
public:
@@ -17,7 +17,7 @@
::aos::EventLoop *event_loop,
std::function<
void(const T &output,
- std::map<std::string, std::shared_ptr<Falcon>> falcon_map)>
+ std::map<std::string, std::shared_ptr<TalonFX>> talonfx_map)>
write_callback)
: LoopOutputHandler<T>(event_loop, "/superstructure"),
write_callback_(write_callback) {
@@ -27,8 +27,8 @@
}
void HandleCANConfiguration(const CANConfiguration &configuration) {
- for (auto &[_, falcon] : falcon_map_) {
- falcon->PrintConfigs();
+ for (auto &[_, talonfx] : talonfx_map_) {
+ talonfx->PrintConfigs();
}
if (configuration.reapply()) {
@@ -36,33 +36,37 @@
}
}
- void add_falcon(std::string_view name, std::shared_ptr<Falcon> falcon) {
- falcon_map_.insert({name, std::move(falcon)});
+ void add_talonfx(std::string_view name, std::shared_ptr<TalonFX> talonfx) {
+ talonfx_map_.insert({name, std::move(talonfx)});
}
static constexpr int kGenericCANWriterPriority = 35;
private:
void WriteConfigs() {
- for (auto &[_, falcon] : falcon_map_) {
- falcon->WriteConfigs();
+ for (auto &[_, talonfx] : talonfx_map_) {
+ talonfx->WriteConfigs();
}
}
- void Write(const T &output) override { write_callback_(output, falcon_map_); }
+ void Write(const T &output) override {
+ write_callback_(output, talonfx_map_);
+ }
void Stop() override {
AOS_LOG(WARNING, "Generic CAN output too old.\n");
- for (auto &[_, falcon] : falcon_map_) {
- falcon->WriteVoltage(0);
+ for (auto &[_, talonfx] : talonfx_map_) {
+ talonfx->WriteVoltage(0);
}
}
- // Maps each name to a falcon to let the caller retreive them when writing
- std::map<std::string_view, std::shared_ptr<Falcon>> falcon_map_;
+ // Maps each name to a talonfx to let the caller retreive them when
+ // writing
+ std::map<std::string_view, std::shared_ptr<TalonFX>> talonfx_map_;
- std::function<void(const T &output,
- std::map<std::string, std::shared_ptr<Falcon>> falcon_map)>
+ std::function<void(
+ const T &output,
+ std::map<std::string, std::shared_ptr<TalonFX>> talonfx_map)>
write_callback_;
};
diff --git a/frc971/wpilib/swerve/BUILD b/frc971/wpilib/swerve/BUILD
index 9f559f6..4493781 100644
--- a/frc971/wpilib/swerve/BUILD
+++ b/frc971/wpilib/swerve/BUILD
@@ -13,8 +13,8 @@
"//aos/logging",
"//frc971:can_configuration_fbs",
"//frc971/control_loops/drivetrain/swerve:swerve_drivetrain_output_fbs",
- "//frc971/wpilib:falcon",
"//frc971/wpilib:loop_output_handler",
+ "//frc971/wpilib:talonfx",
"//third_party:phoenix6",
],
)
@@ -25,6 +25,6 @@
"swerve_module.h",
],
deps = [
- "//frc971/wpilib:falcon",
+ "//frc971/wpilib:talonfx",
],
)
diff --git a/frc971/wpilib/swerve/swerve_drivetrain_writer.cc b/frc971/wpilib/swerve/swerve_drivetrain_writer.cc
index bfc5d73..e4b4ee9 100644
--- a/frc971/wpilib/swerve/swerve_drivetrain_writer.cc
+++ b/frc971/wpilib/swerve/swerve_drivetrain_writer.cc
@@ -14,10 +14,10 @@
event_loop->OnRun([this]() { WriteConfigs(); });
}
-void DrivetrainWriter::set_falcons(std::shared_ptr<SwerveModule> front_left,
- std::shared_ptr<SwerveModule> front_right,
- std::shared_ptr<SwerveModule> back_left,
- std::shared_ptr<SwerveModule> back_right) {
+void DrivetrainWriter::set_talonfxs(std::shared_ptr<SwerveModule> front_left,
+ std::shared_ptr<SwerveModule> front_right,
+ std::shared_ptr<SwerveModule> back_left,
+ std::shared_ptr<SwerveModule> back_right) {
front_left_ = std::move(front_left);
front_right_ = std::move(front_right);
back_left_ = std::move(back_left);
diff --git a/frc971/wpilib/swerve/swerve_drivetrain_writer.h b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
index 4bd6639..d02d4dc 100644
--- a/frc971/wpilib/swerve/swerve_drivetrain_writer.h
+++ b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
@@ -5,9 +5,9 @@
#include "frc971/can_configuration_generated.h"
#include "frc971/control_loops/drivetrain/swerve/swerve_drivetrain_output_generated.h"
-#include "frc971/wpilib/falcon.h"
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/swerve/swerve_module.h"
+#include "frc971/wpilib/talonfx.h"
namespace frc971 {
namespace wpilib {
@@ -22,10 +22,10 @@
DrivetrainWriter(::aos::EventLoop *event_loop, int drivetrain_writer_priority,
double max_voltage);
- void set_falcons(std::shared_ptr<SwerveModule> front_left,
- std::shared_ptr<SwerveModule> front_right,
- std::shared_ptr<SwerveModule> back_left,
- std::shared_ptr<SwerveModule> back_right);
+ void set_talonfxs(std::shared_ptr<SwerveModule> front_left,
+ std::shared_ptr<SwerveModule> front_right,
+ std::shared_ptr<SwerveModule> back_left,
+ std::shared_ptr<SwerveModule> back_right);
void HandleCANConfiguration(const CANConfiguration &configuration);
diff --git a/frc971/wpilib/swerve/swerve_module.h b/frc971/wpilib/swerve/swerve_module.h
index f449afa..d65547a 100644
--- a/frc971/wpilib/swerve/swerve_module.h
+++ b/frc971/wpilib/swerve/swerve_module.h
@@ -1,23 +1,23 @@
#ifndef FRC971_WPILIB_SWERVE_SWERVE_MODULE_H_
#define FRC971_WPILIB_SWERVE_SWERVE_MODULE_H_
-#include "frc971/wpilib/falcon.h"
+#include "frc971/wpilib/talonfx.h"
namespace frc971 {
namespace wpilib {
namespace swerve {
struct SwerveModule {
- SwerveModule(FalconParams rotation_params, FalconParams translation_params,
+ SwerveModule(TalonFXParams rotation_params, TalonFXParams translation_params,
std::string canbus,
std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
double stator_current_limit, double supply_current_limit)
- : rotation(std::make_shared<Falcon>(rotation_params, canbus, signals,
- stator_current_limit,
- supply_current_limit)),
- translation(std::make_shared<Falcon>(translation_params, canbus,
- signals, stator_current_limit,
- supply_current_limit)) {}
+ : rotation(std::make_shared<TalonFX>(rotation_params, canbus, signals,
+ stator_current_limit,
+ supply_current_limit)),
+ translation(std::make_shared<TalonFX>(translation_params, canbus,
+ signals, stator_current_limit,
+ supply_current_limit)) {}
void WriteModule(
const frc971::control_loops::drivetrain::swerve::SwerveModuleOutput
@@ -35,8 +35,8 @@
translation->WriteCurrent(translation_current, max_voltage);
}
- std::shared_ptr<Falcon> rotation;
- std::shared_ptr<Falcon> translation;
+ std::shared_ptr<TalonFX> rotation;
+ std::shared_ptr<TalonFX> translation;
};
} // namespace swerve
diff --git a/frc971/wpilib/falcon.cc b/frc971/wpilib/talonfx.cc
similarity index 68%
rename from frc971/wpilib/falcon.cc
rename to frc971/wpilib/talonfx.cc
index deeb9f8..dd30f9d 100644
--- a/frc971/wpilib/falcon.cc
+++ b/frc971/wpilib/talonfx.cc
@@ -1,11 +1,11 @@
-#include "frc971/wpilib/falcon.h"
+#include "frc971/wpilib/talonfx.h"
-using frc971::wpilib::Falcon;
using frc971::wpilib::kMaxBringupPower;
+using frc971::wpilib::TalonFX;
-Falcon::Falcon(int device_id, bool inverted, std::string canbus,
- std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
- double stator_current_limit, double supply_current_limit)
+TalonFX::TalonFX(int device_id, bool inverted, std::string canbus,
+ std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
+ double stator_current_limit, double supply_current_limit)
: talon_(device_id, canbus),
device_id_(device_id),
inverted_(inverted),
@@ -38,24 +38,24 @@
signals->push_back(&duty_cycle_);
}
-Falcon::Falcon(FalconParams params, std::string canbus,
- std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
- double stator_current_limit, double supply_current_limit)
- : Falcon(params.device_id, params.inverted, canbus, signals,
- stator_current_limit, supply_current_limit) {}
+TalonFX::TalonFX(TalonFXParams params, std::string canbus,
+ std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
+ double stator_current_limit, double supply_current_limit)
+ : TalonFX(params.device_id, params.inverted, canbus, signals,
+ stator_current_limit, supply_current_limit) {}
-void Falcon::PrintConfigs() {
+void TalonFX::PrintConfigs() {
ctre::phoenix6::configs::TalonFXConfiguration configuration;
ctre::phoenix::StatusCode status =
talon_.GetConfigurator().Refresh(configuration);
if (!status.IsOK()) {
- AOS_LOG(ERROR, "Failed to get falcon configuration: %s: %s",
+ AOS_LOG(ERROR, "Failed to get talonfx motor configuration: %s: %s",
status.GetName(), status.GetDescription());
}
AOS_LOG(INFO, "configuration: %s", configuration.ToString().c_str());
}
-void Falcon::WriteConfigs() {
+void TalonFX::WriteConfigs() {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
current_limits.StatorCurrentLimit = stator_current_limit_;
current_limits.StatorCurrentLimitEnable = true;
@@ -75,15 +75,15 @@
ctre::phoenix::StatusCode status =
talon_.GetConfigurator().Apply(configuration);
if (!status.IsOK()) {
- AOS_LOG(ERROR, "Failed to set falcon configuration: %s: %s",
+ AOS_LOG(ERROR, "Failed to set talonfx motor configuration: %s: %s",
status.GetName(), status.GetDescription());
}
PrintConfigs();
}
-ctre::phoenix::StatusCode Falcon::WriteCurrent(double current,
- double max_voltage) {
+ctre::phoenix::StatusCode TalonFX::WriteCurrent(double current,
+ double max_voltage) {
ctre::phoenix6::controls::TorqueCurrentFOC control(
static_cast<units::current::ampere_t>(current));
// Using 0_Hz here makes it a one-shot update.
@@ -91,14 +91,14 @@
control.MaxAbsDutyCycle = SafeSpeed(max_voltage);
ctre::phoenix::StatusCode status = talon()->SetControl(control);
if (!status.IsOK()) {
- AOS_LOG(ERROR, "Failed to write control to falcon %d: %s: %s", device_id(),
- status.GetName(), status.GetDescription());
+ AOS_LOG(ERROR, "Failed to write control to talonfx motor %d: %s: %s",
+ device_id(), status.GetName(), status.GetDescription());
}
return status;
}
-ctre::phoenix::StatusCode Falcon::WriteVoltage(double voltage) {
+ctre::phoenix::StatusCode TalonFX::WriteVoltage(double voltage) {
ctre::phoenix6::controls::DutyCycleOut control(SafeSpeed(voltage));
// Using 0_Hz here makes it a one-shot update.
@@ -107,16 +107,16 @@
ctre::phoenix::StatusCode status = talon()->SetControl(control);
if (!status.IsOK()) {
- AOS_LOG(ERROR, "Failed to write control to falcon %d: %s: %s", device_id(),
- status.GetName(), status.GetDescription());
+ AOS_LOG(ERROR, "Failed to write control to talonfx motor %d: %s: %s",
+ device_id(), status.GetName(), status.GetDescription());
}
return status;
}
-void Falcon::SerializePosition(flatbuffers::FlatBufferBuilder *fbb,
- double gear_ratio) {
- control_loops::CANFalcon::Builder builder(*fbb);
+void TalonFX::SerializePosition(flatbuffers::FlatBufferBuilder *fbb,
+ double gear_ratio) {
+ control_loops::CANTalonFX::Builder builder(*fbb);
builder.add_id(device_id_);
builder.add_device_temp(device_temp());
builder.add_supply_voltage(supply_voltage());
@@ -128,8 +128,8 @@
last_position_offset_ = builder.Finish();
}
-std::optional<flatbuffers::Offset<control_loops::CANFalcon>>
-Falcon::TakeOffset() {
+std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
+TalonFX::TakeOffset() {
auto option_offset = last_position_offset_;
last_position_offset_.reset();
diff --git a/frc971/wpilib/falcon.h b/frc971/wpilib/talonfx.h
similarity index 76%
rename from frc971/wpilib/falcon.h
rename to frc971/wpilib/talonfx.h
index 804c7a0..603f4a2 100644
--- a/frc971/wpilib/falcon.h
+++ b/frc971/wpilib/talonfx.h
@@ -1,5 +1,5 @@
-#ifndef FRC971_WPILIB_FALCON_H_
-#define FRC971_WPILIB_FALCON_H_
+#ifndef FRC971_WPILIB_TALONFX_MOTOR_H_
+#define FRC971_WPILIB_TALONFX_MOTOR_H_
#include <chrono>
#include <cinttypes>
@@ -18,7 +18,7 @@
namespace frc971 {
namespace wpilib {
-struct FalconParams {
+struct TalonFXParams {
int device_id;
bool inverted;
};
@@ -26,16 +26,17 @@
static constexpr units::frequency::hertz_t kCANUpdateFreqHz = 200_Hz;
static constexpr double kMaxBringupPower = 12.0;
-// Gets info from and writes to falcon motors using the TalonFX controller.
-class Falcon {
+// Class which represents a motor controlled by a TalonFX motor controller over
+// CAN.
+class TalonFX {
public:
- Falcon(int device_id, bool inverted, std::string canbus,
- std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
- double stator_current_limit, double supply_current_limit);
+ TalonFX(int device_id, bool inverted, std::string canbus,
+ std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
+ double stator_current_limit, double supply_current_limit);
- Falcon(FalconParams params, std::string canbus,
- std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
- double stator_current_limit, double supply_current_limit);
+ TalonFX(TalonFXParams params, std::string canbus,
+ std::vector<ctre::phoenix6::BaseStatusSignal *> *signals,
+ double stator_current_limit, double supply_current_limit);
void PrintConfigs();
@@ -46,11 +47,11 @@
ctre::phoenix6::hardware::TalonFX *talon() { return &talon_; }
- // The position of the Falcon output shaft is multiplied by gear_ratio
+ // The position of the TalonFX output shaft is multiplied by gear_ratio
void SerializePosition(flatbuffers::FlatBufferBuilder *fbb,
double gear_ratio);
- std::optional<flatbuffers::Offset<control_loops::CANFalcon>> TakeOffset();
+ std::optional<flatbuffers::Offset<control_loops::CANTalonFX>> TakeOffset();
int device_id() const { return device_id_; }
float device_temp() const { return device_temp_.GetValue().value(); }
@@ -101,9 +102,9 @@
double stator_current_limit_;
double supply_current_limit_;
- std::optional<flatbuffers::Offset<control_loops::CANFalcon>>
+ std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
last_position_offset_;
};
} // namespace wpilib
} // namespace frc971
-#endif // FRC971_WPILIB_FALCON_H_
+#endif // FRC971_WPILIB_TALONFX_MOTOR_H_