Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add grafana #152

Merged
merged 16 commits into from
May 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -102,5 +102,6 @@
"future": "cpp",
"scoped_allocator": "cpp",
"shared_mutex": "cpp"
}
},
"rpc.enabled": true
}
Binary file added firmware/pros-grafana-lib.a
Binary file not shown.
411 changes: 0 additions & 411 deletions include/autoPaths.hpp

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion include/auton.h
Original file line number Diff line number Diff line change
@@ -1 +1 @@
#define AUTON 8
#define AUTON 4
Original file line number Diff line number Diff line change
@@ -1,25 +1,24 @@
#pragma once

#include "api.h"
#include "drivetrain.hpp"
#include "abstractDrivetrain.hpp"
#include "utils/vector.hpp"

namespace Pronounce
{
/**
* Omnidirectional drive type, used for X-Drive/Mecanum drive
*/
class OmniDrivetrain : public Drivetrain {
class AbstractHolonomicDrivetrain : public AbstractDrivetrain {
private:

public:
OmniDrivetrain();
OmniDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu);
AbstractHolonomicDrivetrain();

virtual double getSpeed() { return 0; }

virtual void setDriveVectorVelocity(Vector vector) {}
virtual void setDriveVectorVelocity(Vector vector, double rotation) {}

~OmniDrivetrain();
~AbstractHolonomicDrivetrain();
};

} // namespace Pronounce
42 changes: 42 additions & 0 deletions include/chassis/chassis.puml
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
@startuml
abstract "AbstractDrivetrain" as abstractDrivetrain
abstract "AbstractHolonomicDrivetrain" as abstractHolonomicDrivetrain
abstract "AbstractTankDrivetrain" as abstractTankDrivetrain

abstractDrivetrain <|-- abstractHolonomicDrivetrain
abstractDrivetrain <|-- abstractTankDrivetrain

abstract "SimDrivetrain" as simDrivetrain
class "SimTankDrivetrain" as simTankDrivetrain

abstractDrivetrain <|-- simDrivetrain
simDrivetrain <|-- simTankDrivetrain
abstractTankDrivetrain <|-- simTankDrivetrain

abstract "Drivetrain" as drivetrain

abstractDrivetrain <|-- drivetrain

abstract "XDrive" as xdrive

drivetrain <|-- xdrive
abstractHolonomicDrivetrain <|-- xdrive

abstract "MecanumDrivetrain" as mecanumDrivetrain

drivetrain <|-- mecanumDrivetrain
abstractHolonomicDrivetrain <|-- mecanumDrivetrain

abstract "TankDrivetrain" as tankDrivetrain

drivetrain <|-- tankDrivetrain
abstractTankDrivetrain <|-- tankDrivetrain

class "Pros" as pros

drivetrain ..> pros
xdrive ..> pros
mecanumDrivetrain ..> pros
tankDrivetrain ..> pros

@enduml
44 changes: 2 additions & 42 deletions include/chassis/drivetrain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,58 +12,18 @@ namespace Pronounce {
class Drivetrain : public AbstractDrivetrain {
protected:

MotorGroup leftMotors;
MotorGroup rightMotors;

pros::Imu* imu;

public:
Drivetrain();
Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu);
Drivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu);
Drivetrain(MotorGroup leftMotors, MotorGroup rightMotors, pros::Imu* imu);

/**
* Get average temperature of all the motors.
*/
double getTemp();
virtual double getTemp() { return 0; }

/**
* Get average speed of all the motors
*/
double getSpeed();

pros::Imu* getImu() {
return imu;
}

void setImu(pros::Imu* imu) {
this->imu = imu;
}

MotorGroup getLeftMotors() {
return leftMotors;
}

void setLeftMotors(MotorGroup leftMotors) {
this->leftMotors = leftMotors;
}

void addLeftMotor(pros::Motor* motor) {
this->leftMotors.addMotor(motor);
}

MotorGroup getRightMotors() {
return rightMotors;
}

void setRightMotors(MotorGroup rightMotors) {
this->rightMotors = rightMotors;
}

void addRightMotor(pros::Motor* motor) {
this->rightMotors.addMotor(motor);
}
virtual double getSpeed() { return 0; }

~Drivetrain() {

Expand Down
4 changes: 2 additions & 2 deletions include/chassis/mecanumDrivetrain.hpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
#pragma once

#include "api.h"
#include "omniDrivetrain.hpp"
#include "abstractHolonomicDrivetrain.hpp"
#include "utils/vector.hpp"
#include "odometry/threeWheelOdom.hpp"

namespace Pronounce {
class MecanumDrivetrain : public OmniDrivetrain {
class MecanumDrivetrain : public AbstractHolonomicDrivetrain {
private:
pros::Motor* frontLeft;
pros::Motor* frontRight;
Expand Down
2 changes: 1 addition & 1 deletion include/chassis/simDrivetrain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace Pronounce {
* @brief A class for all simulator drivetrains
*
*/
class SimDrivetrain {
class SimDrivetrain : public AbstractDrivetrain {
private:
Position* position;
double resetOrientation = 0.0;
Expand Down
30 changes: 1 addition & 29 deletions include/chassis/tankDrive.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,35 +10,7 @@ namespace Pronounce {
private:

public:
TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu);
TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth);
TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu);
TankDrivetrain(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* midLeft, pros::Motor* midRight, pros::Motor* backLeft, pros::Motor* backRight, pros::Imu* imu, double trackWidth);

double getSpeed() override {
return (this->getLeftMotors().get_actual_velocity() + this->getRightMotors().get_actual_velocity()) / 2;
}

void skidSteerVelocity(double speed, double turn) {
this->getLeftMotors().move_velocity(speed + turn);
this->getRightMotors().move_velocity(speed - turn);
}

void skidSteerVoltage(double speed, double turn) {
this->getLeftMotors().move_voltage(speed + turn);
this->getRightMotors().move_voltage(speed - turn);
}

void tankSteerVelocity(double leftSpeed, double rightSpeed) {
this->getLeftMotors().move_velocity(leftSpeed);
this->getRightMotors().move_velocity(rightSpeed);
}

void tankSteerVoltage(double leftSpeed, double rightSpeed) {
this->getLeftMotors().move_voltage(leftSpeed);
this->getRightMotors().move_voltage(rightSpeed);
}


~TankDrivetrain();
};
} // namespace Pronounce
Expand Down
93 changes: 54 additions & 39 deletions include/chassis/xdrive.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,54 +2,69 @@

#include "api.h"
#include "drivetrain.hpp"
#include "abstractHolonomicDrivetrain.hpp"
#include "utils/vector.hpp"

#define AUTON_CONTROL 0
#define DRIVER_CONTROL 1
namespace Pronounce {
class XDrive : public Drivetrain, AbstractHolonomicDrivetrain {
private:

class XDrive {
private:
pros::Motor* frontLeftMotor;
pros::Motor* frontRightMotor;
pros::Motor* backLeftMotor;
pros::Motor* backRightMotor;

// Motors, have to be pointers because they would
// not be modifiable otherwise
pros::Motor* frontRight;
pros::Motor* frontLeft;
pros::Motor* backRight;
pros::Motor* backLeft;
double trackWidth;
double wheelAngle;

// Motion control wheels
public:
XDrive(pros::Motor* frontLeft,
pros::Motor* frontRight,
pros::Motor* backLeft,
pros::Motor* backRight) {
frontLeftMotor = frontLeft;
frontRightMotor = frontRight;
backLeftMotor = backLeft;
backRightMotor = backRight;

pros::Imu* imu;
trackWidth = 15;
wheelAngle = M_PI_4;
}

int currentState;
XDrive(pros::Motor* frontLeft, pros::Motor* frontRight, pros::Motor* backLeft, pros::Motor* backRight, double trackWidth, double wheelAngle) {
frontLeftMotor = frontLeft;
frontRightMotor = frontRight;
backLeftMotor = backLeft;
backRightMotor = backRight;

public:
this->trackWidth = trackWidth;
this->wheelAngle = wheelAngle;

XDrive(pros::Motor* frontRight,
pros::Motor* frontLeft,
pros::Motor* backRight,
pros::Motor* backLeft,
pros::Imu* imu) {
}

this->frontRight = frontRight;
this->frontLeft = frontLeft;
this->backRight = backRight;
this->backLeft = backLeft;
void setDriveVectorVelocity(Vector vector, double rotation) {
this->frontLeftMotor->move_velocity(vector.getCartesian().getY() + vector.getCartesian().getX() + rotation);
this->frontRightMotor->move_velocity(vector.getCartesian().getY() - vector.getCartesian().getX() - rotation);
this->backLeftMotor->move_velocity(vector.getCartesian().getY() - vector.getCartesian().getX() + rotation);
this->backRightMotor->move_velocity(vector.getCartesian().getY() + vector.getCartesian().getX() - rotation);
}

this->imu = imu;
} //! Move implementation to src/chassis/xdrive.cpp
void setDriveVectorVelocity(Vector vector) {
this->setDriveVectorVelocity(vector, 0);
}

/**
* Get the average drivetrain temperature
*
* @return Average of the 4 wheels
*/
double getAvgTemp() {
double total = this->frontLeftMotor->get_temperature() +
this->frontRightMotor->get_temperature() +
this->backLeftMotor->get_temperature() +
this->backRightMotor->get_temperature();
return total / 4;
}

/**
* Get the average drivetrain temperature
*
* @return Average of the 4 wheels
*/
double getAvgTemp() {
double total = this->frontLeft->get_temperature() +
this->frontRight->get_temperature() +
this->backLeft->get_temperature() +
this->backRight->get_temperature();
return total / 4;
} //! Move implementation to src/chassis/xdrive.cpp

};
};
}
1 change: 1 addition & 0 deletions include/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@
#define AUTON_RIGHT_DOUBLE_STEAL 6
#define AUTON_NONE 7
#define AUTON_SKILLS 8
#define AUTON_TEST 9
19 changes: 11 additions & 8 deletions include/main.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,10 @@
#include "okapi/api.hpp"
//#include "pros/api_legacy.h"

/**
* User defined imports
*/
// grafanalib includes
#include "pros-grafana-lib/api.h"

// 2654lib includes

#include "autoPaths.hpp"

Expand All @@ -60,7 +61,7 @@
#include "chassis/abstractDrivetrain.hpp"
#include "chassis/drivetrain.hpp"
#include "chassis/mecanumDrivetrain.hpp"
#include "chassis/omniDrivetrain.hpp"
#include "chassis/abstractHolonomicDrivetrain.hpp"
#include "chassis/tankDrive.hpp"
#include "chassis/xdrive.hpp"

Expand Down Expand Up @@ -92,13 +93,17 @@
#include "position/odomWheel.hpp"
#include "position/trackingWheel.hpp"

// State Machine
#include "stateMachine/behavior.hpp"
#include "stateMachine/sequence.hpp"
#include "stateMachine/stateController.hpp"
#include "stateMachine/wait.hpp"

// Utils
#include "utils/motorGroup.hpp"
#include "utils/path.hpp"
#include "utils/pointUtil.hpp"
#include "utils/position.hpp"
#include "utils/purePursuitProfile.hpp"
#include "utils/purePursuitProfileManager.hpp"
#include "utils/quadraticSplinePath.hpp"
#include "utils/runningAverage.hpp"
#include "utils/splinePath.hpp"
Expand All @@ -108,7 +113,6 @@
#include "utils/motorGroup.hpp"

// Vision
#include "vision/tippingVision.hpp"


/**
Expand All @@ -123,7 +127,6 @@
// using namespace pros::literals;
using namespace okapi;
using namespace Pronounce; // General Lib
using namespace PronounceTiP; // TiP Exclusive libs

/**
* Prototypes for the competition control tasks are redefined here to ensure
Expand Down
4 changes: 1 addition & 3 deletions include/motionControl/balance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,7 @@ namespace Pronounce {

uint32_t startTime = pros::millis();

while (!this->isBalanced()) {// && pros::millis() - startTime < 2000) {
printf("Is balanced: %d\n", this->isBalanced());

while (!this->isBalanced()) {// && pros::millis() - startTime < 2000) {
this->update();
pros::Task::delay(waitTime);
}
Expand Down
Loading