Skip to content

Commit

Permalink
use subzero ns
Browse files Browse the repository at this point in the history
  • Loading branch information
having11 committed May 21, 2024
1 parent 211280f commit 3464560
Show file tree
Hide file tree
Showing 25 changed files with 80 additions and 20 deletions.
1 change: 1 addition & 0 deletions lib/cpp/subzero/logging/ConsoleLogger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <wpi/json.h>

using namespace subzero;
using namespace Logging;

ConsoleLogger::ConsoleLogger() {
Expand Down
1 change: 1 addition & 0 deletions lib/cpp/subzero/logging/ShuffleboardLogger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <wpi/json.h>

using namespace subzero;
using namespace Logging;

ShuffleboardLogger::ShuffleboardLogger() {}
Expand Down
2 changes: 2 additions & 0 deletions lib/cpp/subzero/target/TurnToPose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc/trajectory/TrajectoryGenerator.h>

using namespace subzero;

TurnToPose::TurnToPose(TurnToPoseConfig config,
std::function<frc::Pose2d()> poseGetter,
std::function<frc::Field2d *()> fieldGetter)
Expand Down
2 changes: 2 additions & 0 deletions lib/cpp/subzero/vision/TargetTracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

#include <ranges>

using namespace subzero;

TargetTracker::TargetTracker(TargetTrackerConfig config,
std::function<frc::Pose2d()> poseGetter,
std::function<frc::Field2d *()> fieldGetter)
Expand Down
5 changes: 4 additions & 1 deletion lib/include/subzero/autonomous/AutoFactory.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#include "subzero/logging/ConsoleLogger.h"

namespace subzero {

/**
* @brief Safely get an auto command from PPLib without the risk of crashing
* from a missing auto file
Expand Down Expand Up @@ -80,4 +82,5 @@ template <typename T> class AutoFactory {

return PathPlannerPathFromName(m_autos.at(type));
}
};
};
}
4 changes: 3 additions & 1 deletion lib/include/subzero/constants/ColorConstants.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <frc/util/Color.h>
#include <frc/util/Color8Bit.h>

namespace subzero {
namespace ColorConstants {
static const frc::Color8Bit kYellow{0xE5, 0xD5, 0x24};
static const frc::Color8Bit kPurple{0x57, 0x14, 0xE8};
Expand All @@ -13,4 +14,5 @@ static const frc::Color8Bit kTeal{0x18, 0x9B, 0xCE};
static const frc::Color8Bit kOrange{0xE8, 0x61, 0x19};
static const frc::Color8Bit kAcidGreen{0xB0, 0xBF, 0x1A};
static const frc::Color8Bit kBlack{0x00, 0x00, 0x00};
} // namespace ColorConstants
} // namespace ColorConstants
}
4 changes: 3 additions & 1 deletion lib/include/subzero/drivetrain/SwerveUtils.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

namespace subzero {
class SwerveUtils {
public:
/**
Expand Down Expand Up @@ -50,4 +51,5 @@ class SwerveUtils {
* @return An angle (in radians) from 0 and 2*PI (exclusive).
*/
static double WrapAngle(double _angle);
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/frc/smartdashboard/ModifiableChooser.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include <string>
#include <vector>

namespace subzero {

/**
* @brief A SmartDashboard drop-down that can have its options dynamically
* change
Expand Down Expand Up @@ -261,4 +263,5 @@ template <typename T> class ModifiableChooser : public wpi::Sendable {
kSelected, std::bind(&ModifiableChooser::GetNtSelected, this),
[this](std::string_view val) { SetNtSelected(std::string{val}); });
}
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/frc/smartdashboard/TaggedChooser.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

#include "subzero/frc/smartdashboard/ModifiableChooser.h"

namespace subzero {

/**
* @brief Each key of type T has a vector<string> of tags; accepts a list of
* groups that each have a name and list of possible tags that are mutually
Expand Down Expand Up @@ -177,4 +179,5 @@ template <typename TKey> class TaggedChooser {
std::vector<TaggedChooserSendableGroup> m_groups;
ModifiableChooser<TKey> m_chooser;
std::string m_chooserName;
};
};
}
5 changes: 3 additions & 2 deletions lib/include/subzero/logging/ConsoleLogger.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include "subzero/logging/ILogger.h"

namespace subzero {
/**
* @brief Outputs formatted strings to stdout
*
Expand Down Expand Up @@ -67,8 +68,9 @@ class ConsoleLogger : ILogger {
<< std::endl;
}
};
}

#define ConsoleWriter ConsoleLogger::getInstance()
#define ConsoleWriter subzero::ConsoleLogger::getInstance()
/**
* @brief Shortcut to log at the Logging::Level::Info level from a command
* composition
Expand All @@ -87,5 +89,4 @@ class ConsoleLogger : ILogger {
frc2::InstantCommand([] { \
ConsoleWriter.logVerbose(key, fmt, __VA_ARGS__); \
}).ToPtr()

#endif
5 changes: 4 additions & 1 deletion lib/include/subzero/logging/ILogger.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@

#include "subzero/utils/UtilConstants.h"

namespace subzero {

/**
* @brief Logger interface
*
Expand Down Expand Up @@ -95,4 +97,5 @@ class ILogger {
inline bool shouldLog(Logging::Level level) {
return static_cast<int>(level) >= static_cast<int>(Logging::kMinLogLevel);
}
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/logging/ShuffleboardLogger.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include "subzero/logging/ILogger.h"

namespace subzero {

/**
* @brief Outputs formatted information to SmartDashboard
*
Expand Down Expand Up @@ -67,4 +69,5 @@ class ShuffleboardLogger : ILogger {

return val;
}
};
};
}
4 changes: 3 additions & 1 deletion lib/include/subzero/motor/PidMotorController.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

#include "subzero/logging/ConsoleLogger.h"

namespace subzero {
struct PidSettings {
double p, i, d, iZone, ff;
};
Expand Down Expand Up @@ -302,4 +303,5 @@ class PidMotorControllerTuner {
class RevPidMotorController
: public PidMotorController<rev::CANSparkMax, rev::SparkPIDController,
rev::SparkRelativeEncoder,
rev::SparkAbsoluteEncoder> {};
rev::SparkAbsoluteEncoder> {};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/motor/PidMotorControllerPair.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#include "subzero/logging/ConsoleLogger.h"
#include "subzero/motor/PidMotorController.h"

namespace subzero {

/**
* @brief Encapsulates a pair of motors that should be treated as a single unit
*
Expand Down Expand Up @@ -147,4 +149,5 @@ class PidMotorControllerPairTuner {
private:
PidMotorControllerPair<TMotor, TController, TRelativeEncoder,
TAbsoluteEncoder> &m_controllerPair;
};
};
}
3 changes: 3 additions & 0 deletions lib/include/subzero/singleaxis/BaseSingleAxisSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
#include "subzero/motor/PidMotorController.h"
#include "subzero/singleaxis/ISingleAxisSubsystem.h"

namespace subzero {

/**
* @brief The ultimate solution for turrets, arms, and much more. This class
* allows for absolute, relative, and joystick control across both linear and
Expand Down Expand Up @@ -330,3 +332,4 @@ class BaseSingleAxisSubsystem
frc2::CommandPtr m_resetEncCmd = frc2::InstantCommand([] {}).ToPtr();
frc::MechanismLigament2d *m_ligament2d;
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/singleaxis/ISingleAxisSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
#include <memory>
#include <string>

namespace subzero {

/**
* @brief Describes the axis for simulation
*
Expand Down Expand Up @@ -266,4 +268,5 @@ template <typename Distance> class ISingleAxisSubsystem {
*
*/
virtual void Stop() = 0;
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/singleaxis/LinearSingleAxisSubsystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#include "subzero/singleaxis/BaseSingleAxisSubsystem.h"

namespace subzero {

/**
* @brief A single axis representing a linear path of motion in meters
*
Expand Down Expand Up @@ -70,4 +72,5 @@ class LinearSingleAxisSubsystem
"Running with a velocity is not supported for linear subsystems!%s",
"");
}
};
};
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

#include "subzero/singleaxis/BaseSingleAxisSubsystem.h"

namespace subzero {

/**
* @brief A single axis representing a circular path of motion in degrees
*
Expand Down Expand Up @@ -74,4 +76,5 @@ class RotationalSingleAxisSubsystem

protected:
units::meter_t m_armatureLength;
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/target/ITurnToTarget.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include <frc/geometry/Rotation2d.h>
#include <frc/kinematics/ChassisSpeeds.h>

namespace subzero {

/**
* @brief Interface for classes that move towards a target while maintaining
* driver input
Expand All @@ -17,4 +19,5 @@ class ITurnToTarget {
double correctionFactor) = 0;
virtual bool AtGoal() = 0;
virtual void Update() = 0;
};
};
}
5 changes: 4 additions & 1 deletion lib/include/subzero/target/TurnToPose.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "subzero/target/ITurnToTarget.h"

namespace subzero {

/**
* @brief Allows the robot/an axis to face an arbitrary Pose2d
*
Expand Down Expand Up @@ -146,4 +148,5 @@ class TurnToPose : public ITurnToTarget {
std::optional<units::degree_t> m_targetAngle;
units::degree_t m_targetHeading;
frc::ChassisSpeeds m_speeds;
};
};
}
3 changes: 2 additions & 1 deletion lib/include/subzero/utils/DetectionParser.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

#include "subzero/utils/UtilConstants.h"

namespace subzero {
namespace DetectionParser {

struct BoundingBox {
Expand Down Expand Up @@ -54,7 +55,7 @@ struct DetectedObject {
return detectedObjects;
}
};

} // namespace DetectionParser
}

#endif
4 changes: 3 additions & 1 deletion lib/include/subzero/utils/InputUtils.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <cmath>

namespace subzero {
namespace InputUtils {
typedef struct {
double x;
Expand All @@ -25,4 +26,5 @@ DeadzoneAxes CalculateCircularDeadzone(double x, double y,

return {.x = 0, .y = 0, .deadzoneApplied = true};
}
} // namespace InputUtils
} // namespace InputUtils
}
2 changes: 2 additions & 0 deletions lib/include/subzero/utils/UtilConstants.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

namespace subzero {
namespace Logging {
/**
* @brief Levels of logging
Expand All @@ -15,4 +16,5 @@ constexpr auto kMinLogLevel = Level::VERBOSE;

namespace DetectionParser {
enum class ObjectClasses { Cone = 0, Cube = 1, Merge = 2 };
}
}
5 changes: 4 additions & 1 deletion lib/include/subzero/vision/PhotonVisionEstimators.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
#include <utility>
#include <vector>

namespace subzero {

/**
* @brief Combines estimated poses from an aritrary number of PhotonVision
* cameras and applies them to a Holonomic pose estimator
Expand Down Expand Up @@ -148,4 +150,5 @@ class PhotonVisionEstimators {
Eigen::Matrix<double, 3, 1> m_multiTagStdDevs;

units::second_t lastEstTimestamp{0_s};
};
};
}
Loading

0 comments on commit 3464560

Please sign in to comment.