Skip to content

Commit

Permalink
Merge branch 'april_tags' of https://github.com/Team846/monkey_menace
Browse files Browse the repository at this point in the history
…into april_tags
  • Loading branch information
VyaasBaskar committed Jan 25, 2025
2 parents 1e3996e + d7f1fd0 commit 44c8886
Show file tree
Hide file tree
Showing 17 changed files with 43 additions and 25 deletions.
5 changes: 5 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,9 @@
{
"FMS": {
"window": {
"visible": false
}
},
"Keyboard 0 Settings": {
"window": {
"visible": true
Expand Down
7 changes: 5 additions & 2 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,15 @@
"Connections": {
"open": true
},
"Server": {
"Subscribers": {
"Elastic@1": {
"Publishers": {
"open": true
},
"open": true
},
"Server": {
"open": true
},
"visible": true
}
}
6 changes: 4 additions & 2 deletions src/frc846/cpp/frc846/base/Loggable.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,15 @@

namespace frc846::base {

std::string Loggable::Join(std::string p, std::string n) { return p + "/" + n; }
std::string_view Loggable::Join(std::string p, std::string n) {
return p + "/" + n;
}

unsigned int Loggable::GetWarnCount() { return warn_count_; }

unsigned int Loggable::GetErrorCount() { return error_count_; }

std::unordered_set<std::string> Loggable::used_preferences_{};
std::unordered_set<std::string_view> Loggable::used_preferences_{};

unsigned int Loggable::warn_count_ = 0;
unsigned int Loggable::error_count_ = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/frc846/cpp/frc846/control/MotorMonkey.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <rev/SparkMax.h>

#include <iostream>
#include <string>
#include <string_view>

#include "frc846/control/hardware/SparkMXFX_interm.h"
#include "frc846/control/hardware/TalonFX_interm.h"
Expand Down Expand Up @@ -473,7 +473,7 @@ void MotorMonkey::SetSoftLimits(size_t slot_id, units::radian_t forward_limit,
LOG_IF_ERROR("SetSoftLimits");
}

std::string MotorMonkey::parseError(
std::string_view MotorMonkey::parseError(
frc846::control::hardware::ControllerErrorCodes err) {
switch (err) {
case frc846::control::hardware::ControllerErrorCodes::kAllOK: return "All OK";
Expand Down
2 changes: 1 addition & 1 deletion src/frc846/cpp/frc846/control/hardware/TalonFX_interm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ namespace frc846::control::hardware {
bool TalonFX_interm::VerifyConnected() { return talon_.IsAlive(); }

TalonFX_interm::TalonFX_interm(
int can_id, std::string bus, units::millisecond_t max_wait_time)
int can_id, std::string_view bus, units::millisecond_t max_wait_time)
: talon_(can_id, bus), max_wait_time_(max_wait_time) {}

void TalonFX_interm::Tick() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,10 @@ void MCSimulator::Tick() {
units::newton_meter_t torque_output =
frc846::control::calculators::CurrentTorqueCalculator::current_to_torque(
pred_current_, specs);
units::newton_meter_t friction_torque =
specs.stall_torque * specs.friction_loss *
(velocity_ / units::math::abs(velocity_));
if (units::math::abs(velocity_) < 0.01_rad_per_s) { friction_torque = 0_Nm; }
torque_output -= load_;

std::chrono::microseconds current_time =
Expand All @@ -48,6 +52,9 @@ void MCSimulator::Tick() {
units::radians_per_second_t new_velocity =
frc846::control::calculators::VelocityPositionEstimator::predict_velocity(
velocity_, torque_output, loop_time, rotational_inertia_);
new_velocity =
units::radians_per_second_t{std::clamp(new_velocity.to<double>(),
(-specs.free_speed).to<double>(), specs.free_speed.to<double>())};
units::radians_per_second_t avg_velocity = (velocity_ + new_velocity) / 2.0;

position_ =
Expand Down
4 changes: 2 additions & 2 deletions src/frc846/cpp/frc846/robot/GenericRobot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ void GenericRobot::StartCompetition() {
loop.Clear();
} else if (mode == Mode::kAutonomous) {
// Get and run selected auto command
std::string option_name = auto_chooser_.GetSelected();
std::string_view option_name = auto_chooser_.GetSelected();
auto_command_ = autos_[option_name];

if (auto_command_ != nullptr) {
Expand Down Expand Up @@ -222,7 +222,7 @@ void GenericRobot::VerifyHardware() {
generic_robot_container_->VerifyHardware();
}

void GenericRobot::AddAuto(std::string name, frc2::Command* command) {
void GenericRobot::AddAuto(std::string_view name, frc2::Command* command) {
auto_chooser_.AddOption(name, name);
autos_[name] = command;
frc::SmartDashboard::PutData(&auto_chooser_);
Expand Down
6 changes: 3 additions & 3 deletions src/frc846/cpp/frc846/robot/swerve/drivetrain.cc
Original file line number Diff line number Diff line change
Expand Up @@ -212,9 +212,9 @@ DrivetrainReadings DrivetrainSubsystem::ReadFromHardware() {

frc846::robot::swerve::odometry::SwervePose new_pose{
.position = odometry_
.calculate({bearing, steer_positions, drive_positions,
GetPreferenceValue_double("odom_fudge_factor")})
.position,
.calculate({bearing, steer_positions, drive_positions,
GetPreferenceValue_double("odom_fudge_factor")})
.position,
.bearing = bearing,
.velocity = velocity,
};
Expand Down
4 changes: 2 additions & 2 deletions src/frc846/include/frc846/base/FunkyLogSystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ class FunkyLogger {
}

public:
FunkyLogger(std::string pname) : pname_{pname} {};
FunkyLogger(std::string_view pname) : pname_{pname} {};

template <typename... T>
void Log(fmt::format_string<T...> fmt, T&&... args) const {
Expand All @@ -139,4 +139,4 @@ class FunkyLogger {
}
};

} // namespace frc846::base
} // namespace frc846::base
6 changes: 3 additions & 3 deletions src/frc846/include/frc846/base/Loggable.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class Loggable {
static unsigned int GetWarnCount();
static unsigned int GetErrorCount();

static std::string Join(std::string p, std::string n);
static std::string_view Join(std::string p, std::string n);

static std::vector<std::string> ListKeysToPrune();

Expand All @@ -141,12 +141,12 @@ class Loggable {

const std::string name_;

static std::unordered_set<std::string> used_preferences_;
static std::unordered_set<std::string_view> used_preferences_;

static unsigned int warn_count_;
static unsigned int error_count_;

frc846::base::FunkyLogger logger;
};

} // namespace frc846::base
} // namespace frc846::base
2 changes: 1 addition & 1 deletion src/frc846/include/frc846/control/MotorMonkey.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class MotorMonkey {
static void SetSoftLimits(size_t slot_id, units::radian_t forward_limit,
units::radian_t reverse_limit);

static std::string parseError(
static std::string_view parseError(
frc846::control::hardware::ControllerErrorCodes err);

static bool VerifyConnected();
Expand Down
1 change: 1 addition & 0 deletions src/frc846/include/frc846/control/base/motor_specs.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ struct MotorSpecs {
units::ampere_t stall_current;
units::ampere_t free_current;
units::newton_meter_t stall_torque;
double friction_loss = 0.01;
};

/*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ struct MotorConstructionParameters {

frc846::wpilib::unit_kg_m_sq rotational_inertia;

std::string bus = "";
std::string_view bus = "";

units::millisecond_t max_wait_time = 20_ms;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ TalonFX hardware.
*/
class TalonFX_interm : public IntermediateController {
public:
TalonFX_interm(int can_id, std::string bus = "",
TalonFX_interm(int can_id, std::string_view bus = "",
units::millisecond_t max_wait_time = 20_ms);
/*
Tick()
Expand Down
6 changes: 3 additions & 3 deletions src/frc846/include/frc846/robot/GenericRobot.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class GenericRobot : public frc::RobotBase, public frc846::base::Loggable {

void VerifyHardware();

void AddAuto(std::string name, frc2::Command* command);
void AddAuto(std::string_view name, frc2::Command* command);

private:
hal::Handle<HAL_NotifierHandle> notifier_;
Expand All @@ -47,8 +47,8 @@ class GenericRobot : public frc::RobotBase, public frc846::base::Loggable {
GenericRobotContainer* generic_robot_container_;

frc2::Command* auto_command_ = nullptr;
frc::SendableChooser<std::string> auto_chooser_;
std::unordered_map<std::string, frc2::Command*> autos_;
frc::SendableChooser<std::string_view> auto_chooser_;
std::unordered_map<std::string_view, frc2::Command*> autos_;
};

} // namespace frc846::robot
2 changes: 1 addition & 1 deletion src/frc846/include/frc846/robot/swerve/swerve_module.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ struct SwerveModuleCommonConfig {
steer_conv_unit steer_reduction;
drive_conv_unit drive_reduction;

std::string bus = "";
std::string_view bus = "";
};

/*
Expand Down
2 changes: 1 addition & 1 deletion src/y2025/include/rsighandler.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#include <map>

void handler(int sig) {
std::map<int, std::string> sigErrors;
std::map<int, std::string_view> sigErrors;

sigErrors[SIGFPE] = "FATAL ERROR >> Arithmetic Error, SIGFPE";
sigErrors[SIGILL] = "FATAL ERROR >> Illegal Instruction, SIGILL";
Expand Down

0 comments on commit 44c8886

Please sign in to comment.