REVLib - TAMSFormers5212/TAMSformers-Database GitHub Wiki

The REV Library

REVLib Software Documentation

Explains the SparkMaxes and Hardware Client, but doesn't go into code.

REV C++ API Documentation

Similar to the WPILib C++ Documentation. Shows every classs and function.

Including REV classes

just use #include <rev/ and whatever class you want to use.

#include <rev/CANSparkMax.h>
#include <rev/SparkRelativeEncoder.h>
#include <rev/SparkPIDController.h>

Using REV products

When coding in C++, you'll have to enter the namespaces they are members of. In this case, you can automatically use the namespace rev to reduce verbosity.

using namespace rev;

SparkMaxes (Neos and Neo 550s)

You'll create a motor controller in order to interface with the motor.

CANSparkMax m_Motor;

Then, to make things later easier, you should create objects for the encoders on each motor.

SparkRelativeEncoder m_driveEncoder = m_driveMotor.GetEncoder(SparkRelativeEncoder::Type::kHallSensor, 42);
using type kHallSensor and 42 establishes that it is a Neo/Neo 550 encoder

Next, in cases where you will be using a PID controller, you can run the PID controller on the motor controller itself. This runs the PID loop at 1000Hz versus the native 50Hz that the Roborio runs on.

SparkPIDController m_Controller = m_Motor.GetPIDController();

Now, you'll have to initalize the motor controllers with their CAN ID and the control mode.

Shooter::Shooter(int leftMotor, int rightMotor)
: m_leftMotor(leftMotor, CANSparkLowLevel::MotorType::kBrushless),
m_rightMotor(rightMotor, CANSparkLowLevel::MotorType::kBrushless)
{
    resetMotors();
}

Alternatively you could have initalized them in the .h file.

CANSparkMax m_Motor = rev::CANSparkMax(6, CANSparkMaxLowLevel::MotorType::kBrushless);
CANSparkMax m_Motor{8, CANSparkMaxLowLevel::MotorType::kBrushless};

Finally, we like to reset the motor's configuration settings in a resetMotors() function. Although you can set the settings in REV hardware client and burn flash, some teams have reported this to sometimes not save the setting correct randomly, so we also set the configurations in code on startup.

void Shooter::resetMotors(){
m_leftMotor.RestoreFactoryDefaults();

m_leftController.SetP(ksP);
m_leftController.SetI(ksI);
m_leftController.SetD(ksD);
m_leftController.SetFF(ksFF);

m_leftMotor.SetIdleMode(CANSparkBase::IdleMode::kCoast);
m_leftMotor.EnableVoltageCompensation(12.0);
m_leftMotor.SetSmartCurrentLimit(20, 40);
m_leftMotor.SetClosedLoopRampRate(0.2);

m_leftEncoder.SetPositionConversionFactor(((wheelDiameter*MathConstants::pi) / pulleyRatio).value());
m_leftEncoder.SetVelocityConversionFactor((pulleyRatio*wheelDiameter/ 60_s).value());
m_leftEncoder.SetMeasurementPeriod(16);//values that 3005 used apparently
m_leftEncoder.SetAverageDepth(2);
}

Controlling Motors

Set percent

Pass in a value between -1 and 1 to tell the motor what percentage in power it should use. Negative values will cause it to spin in the opposite direction.

m_Motor.Set(percent);

This is fine for prototyping and situations where precise control in position or velocity is unneeded. However, in most cases using a more precise control mode is prefereable.

m_Controller.SetReference(m_goalSpeed.value(), CANSparkMaxLowLevel::ControlType::kVelocity);

m_Controller.SetReference(m_goalPosition.value(), CANSparkMaxLowLevel::ControlType::kPosition);

The SparkMax PID controller also has the option to add in a feedforward value.

m_Controller.SetReference(m_goalSpeed.value(), CANSparkMaxLowLevel::ControlType::kVelocity, 0, m_FF.Calculate(m_goalSpeed).value());

m_Controller.SetReference(m_goalPosition.value(), CANSparkMaxLowLevel::ControlType::kVelocity, 0, m_FF.Calculate(m_goalPosition).value());
⚠️ **GitHub.com Fallback** ⚠️