Skip to content

Commit

Permalink
Formatted to LLVM & 120 char limit
Browse files Browse the repository at this point in the history
  • Loading branch information
superrm11 committed Feb 25, 2024
1 parent 77882f6 commit aade2e8
Show file tree
Hide file tree
Showing 64 changed files with 3,544 additions and 4,219 deletions.
24 changes: 13 additions & 11 deletions include/robot_specs.h
Original file line number Diff line number Diff line change
@@ -1,25 +1,27 @@
#pragma once
#include "../core/include/utils/controls/pid.h"
#include "../core/include/utils/controls/feedback_base.h"
#include "../core/include/utils/controls/pid.h"

/**
* Main robot characterization struct.
* This will be passed to all the major subsystems
* This will be passed to all the major subsystems
* that require info about the robot.
* All distance measurements are in inches.
*/
typedef struct
{
double robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it
typedef struct {
double
robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it

double odom_wheel_diam; ///< the diameter of the wheels used for
double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data
double dist_between_wheels; ///< the distance between centers of the central drive wheels
double odom_wheel_diam; ///< the diameter of the wheels used for
double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data
double dist_between_wheels; ///< the distance between centers of the central drive wheels

double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target
double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less
///< than this value, we can continue driving forward to minimize our distance but
///< will not try to spin around to point directly at the target

Feedback *drive_feedback; ///< the default feedback for autonomous driving
Feedback *turn_feedback; ///< the defualt feedback for autonomous turning
Feedback *drive_feedback; ///< the default feedback for autonomous driving
Feedback *turn_feedback; ///< the defualt feedback for autonomous turning
PID::pid_config_t correction_pid; ///< the pid controller to keep the robot driving in as straight a line as possible

} robot_specs_t;
14 changes: 6 additions & 8 deletions include/subsystems/custom_encoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,30 +5,29 @@
* A wrapper class for the vex encoder that allows the use of 3rd party
* encoders with different tick-per-revolution values.
*/
class CustomEncoder : public vex::encoder
{
class CustomEncoder : public vex::encoder {
typedef vex::encoder super;

public:
public:
/**
* Construct an encoder with a custom number of ticks
* @param port the triport port on the brain the encoder is plugged into
* @param ticks_per_rev the number of ticks the encoder will report for one revolution
*/
*/
CustomEncoder(vex::triport::port &port, double ticks_per_rev);

/**
* sets the stored rotation of the encoder. Any further movements will be from this value
* @param val the numerical value of the angle we are setting to
* @param units the unit of val
*/
*/
void setRotation(double val, vex::rotationUnits units);

/**
* sets the stored position of the encoder. Any further movements will be from this value
* @param val the numerical value of the position we are setting to
* @param units the unit of val
*/
*/
void setPosition(double val, vex::rotationUnits units);

/**
Expand All @@ -52,7 +51,6 @@ class CustomEncoder : public vex::encoder
*/
double velocity(vex::velocityUnits units);


private:
private:
double tick_scalar;
};
45 changes: 20 additions & 25 deletions include/subsystems/flywheel.h
Original file line number Diff line number Diff line change
@@ -1,22 +1,21 @@
#pragma once

#include "../core/include/utils/controls/feedforward.h"
#include "vex.h"
#include "../core/include/robot_specs.h"
#include "../core/include/utils/controls/pid.h"
#include "../core/include/utils/command_structure/auto_command.h"
#include "../core/include/subsystems/screen.h"
#include "../core/include/utils/command_structure/auto_command.h"
#include "../core/include/utils/controls/feedforward.h"
#include "../core/include/utils/controls/pid.h"
#include "vex.h"
#include <atomic>

/**
* a Flywheel class that handles all control of a high inertia spinning disk
* It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed.
* Flywheel is a set and forget class.
* Once you create it you can call spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this
* It gives multiple options for what control system to use in order to control wheel velocity and functions alerting
* the user when the flywheel is up to speed. Flywheel is a set and forget class. Once you create it you can call
* spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this
*
*/
class Flywheel
{
class Flywheel {

public:
// CONSTRUCTORS, GETTERS, AND SETTERS
Expand Down Expand Up @@ -70,10 +69,7 @@ class Flywheel
* @brief check if the feedback controller thinks the flywheel is on target
* @return true if on target
*/
bool is_on_target()
{
return fb.is_on_target();
}
bool is_on_target() { return fb.is_on_target(); }

/**
* @brief Creates a page displaying info about the flywheel
Expand All @@ -85,23 +81,22 @@ class Flywheel
* @brief Creates a new auto command to spin the flywheel at the desired velocity
* @param rpm the rpm to spin at
* @return an auto command to add to a command controller
*/
AutoCommand *SpinRpmCmd(int rpm)
{
*/
AutoCommand *SpinRpmCmd(int rpm) {

return new FunctionCommand([this, rpm]()
{spin_rpm(rpm); return true; });
return new FunctionCommand([this, rpm]() {
spin_rpm(rpm);
return true;
});
}

/**
* @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback controller
* @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback
* controller
* @return an auto command to add to a command controller
*/
AutoCommand *WaitUntilUpToSpeedCmd()
{
return new WaitUntilCondition(
new FunctionCondition([this]()
{ return is_on_target(); }));
AutoCommand *WaitUntilUpToSpeedCmd() {
return new WaitUntilCondition(new FunctionCondition([this]() { return is_on_target(); }));
}

private:
Expand All @@ -116,7 +111,7 @@ class Flywheel
double ratio; ///< ratio between motor and flywheel. For accurate RPM calcualation
std::atomic<double> target_rpm; ///< Desired RPM of the flywheel.
task rpm_task; ///< task that handles spinning the wheel at a given target_rpm
Filter &avger; ///< Moving average to smooth out noise from
Filter &avger; ///< Moving average to smooth out noise from

// Functions for internal use only
/**
Expand Down
11 changes: 4 additions & 7 deletions include/subsystems/layout.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,8 @@
#include <cmath>
#include <functional>

struct SliderCfg{
double &val;
double min;
double max;
struct SliderCfg {
double &val;
double min;
double max;
};



Loading

0 comments on commit aade2e8

Please sign in to comment.