Valor 6800 1.0
Loading...
Searching...
No Matches
valor::NeoController Class Reference
Inheritance diagram for valor::NeoController:
valor::BaseController valor::Loggable

Public Member Functions

 NeoController (valor::NeoControllerType, int canID, valor::NeutralMode mode, bool inverted)
 
void reset () override
 Resets the motor and any state.
 
void applyConfig () override
 
units::turn_t getPosition () override
 Get the motors position.
 
units::ampere_t getCurrent () override
 Get the motors output current.
 
units::turns_per_second_t getSpeed () override
 Get the motors speed.
 
void setEncoderPosition (units::turn_t position) override
 
units::turn_t getAbsEncoderPosition () override
 
void setContinuousWrap (bool wrap, bool saveImmediately=false)
 
void positionSetter (units::turn_t positon, int slot=0) override
 Send the motor to a specific position.
 
void speedSetter (units::turns_per_second_t speed, int slot=0) override
 Send the motor to a specific speed.
 
void setupFollower (int canID, bool followerInverted=false) override
 If a motor is paired with another motor, setup that other motor as a follower.
 
void setPIDF (valor::PIDF pidf, int slot=0, bool saveImmediately=false) override
 Change the PIDF values for the motor.
 
void setForwardLimit (units::turn_t forward, bool saveImmediately=false) override
 Set the forward soft limit for the motor.
 
void setReverseLimit (units::turn_t reverse, bool saveImmediately=false) override
 Set the reverse soft limit for the motor.
 
void setGearRatios (double rotorToSensor, double sensorToMech, bool saveImmediately=false) override
 Set the gear ratios for the motor.
 
void setCurrentLimits (units::ampere_t statorCurrentLimit, units::ampere_t supplyCurrentLimit, units::ampere_t supplyCurrentThreshold, units::second_t supplyTimeThreshold, bool saveImmediately=false)
 
void setNeutralMode (valor::NeutralMode mode, bool saveImmediately=false)
 
void setOpenLoopRamp (units::second_t time, bool saveImmediately=false) override
 
void powerSetter (units::volt_t voltage) override
 
void LoggablePeriodic () override
 Periodic callback for logging updates.
 
units::volt_t calculateAppliedVoltage () override
 
void setSimState (frc::sim::DCMotorSim &) override
 
- Public Member Functions inherited from valor::BaseController
 BaseController (frc::DCMotor _motorSpec)
 Construct a new Valor Controller object.
 
void OnLoggingStart () override
 Hook invoked when logging is started for this object.
 
OperationalMode getOpMode ()
 
TuningMode getTuneMode ()
 
units::turns_per_second_t getMaxMechSpeed ()
 Get the mechanisms's maximum speed.
 
void setVoltageCompensation (units::volt_t _voltageCompensation)
 Setup the voltage compensation for the motor.
 
units::volt_t getVoltageCompensation ()
 
void setPosition (units::turn_t position, int slot=0)
 
virtual void setPositionWithFeedForward (units::turn_t position, units::turns_per_second_t feedforwardVelocity, int slot=0)
 Send the motor to a specific position with a velocity feedforward.
 
void setSpeed (units::turns_per_second_t speed, int slot=0)
 
virtual void powerSetter (units::ampere_t current)
 
virtual void powerSetter (double dutyCycle)
 
template<typename T >
void setPower (T power)
 
void setLimits (units::turn_t reverse, units::turn_t forward, bool saveImmediately=false)
 Set both soft limits for the motor.
 
- Public Member Functions inherited from valor::Loggable
void LogChild (std::string_view name, Loggable *child)
 Register a child Loggable under a named subtree.
 
void LogChild (std::string_view name, wpi::Sendable *child)
 Register a child Sendable under a named subtree.
 
void setLoggingPeriod (units::millisecond_t period)
 Set the minimum period between LoggablePeriodic() invocations.
 
template<>
decltype(Loggable::subscribers) ::iterator addSubscriber (std::string_view field, const std::vector< bool > &defaultValue)
 
template<>
void WriteLogImpl (nt::Publisher *pub, const std::vector< bool > &data)
 
template<>
std::vector< boolReadLogImpl (nt::Subscriber *sub)
 

Static Public Member Functions

static constexpr frc::DCMotor getMotorSpec (NeoControllerType controllerType)
 
- Static Public Member Functions inherited from valor::Loggable
static units::millisecond_t GetLoggingTime ()
 

Additional Inherited Members

- Public Types inherited from valor::BaseController
enum class  OperationalMode { NonOperational , Tuning , Operational }
 
enum class  TuningMode {
  Voltage , Current , DutyCycle , Speed ,
  Position
}
 
- Public Attributes inherited from valor::BaseController
frc::DCMotor motorSpec
 
double rotorToSensor
 
double sensorToMech
 
- Protected Member Functions inherited from valor::Loggable
 Loggable (std::string_view name)
 Construct a Loggable that registers a top-level table name.
 
 Loggable ()
 Default construct an uninitialized Loggable.
 
virtual ~Loggable ()=default
 Virtual destructor.
 
template<typename T >
T WriteLog (std::string_view field, const T &data)
 Publish a value to NetworkTables under the given field.
 
template<typename T >
ReadLog (std::string_view field, const T &defaultValue={})
 Read a value from NetworkTables for the given field.
 
- Protected Attributes inherited from valor::BaseController
units::volt_t voltageCompensation
 

Member Function Documentation

◆ applyConfig()

void valor::NeoController::applyConfig ( )
overridevirtual

Implements valor::BaseController.

◆ calculateAppliedVoltage()

units::volt_t valor::NeoController::calculateAppliedVoltage ( )
overridevirtual

Implements valor::BaseController.

◆ getAbsEncoderPosition()

units::turn_t valor::NeoController::getAbsEncoderPosition ( )
overridevirtual

Implements valor::BaseController.

◆ getCurrent()

units::ampere_t valor::NeoController::getCurrent ( )
overridevirtual

Get the motors output current.

Get the instantaneous current of the motor that the controller owns

Returns
units::ampere_t Instantaneous amperage of the motor

Implements valor::BaseController.

◆ getPosition()

units::turn_t valor::NeoController::getPosition ( )
overridevirtual

Get the motors position.

To be defined by the implemented BaseController class

Returns
units::turn_t Position of the motor

Implements valor::BaseController.

◆ getSpeed()

units::turns_per_second_t valor::NeoController::getSpeed ( )
overridevirtual

Get the motors speed.

To be defined by the implemented BaseController class

Returns
units::turns_per_second_t Speed of the motor

Implements valor::BaseController.

◆ LoggablePeriodic()

void valor::NeoController::LoggablePeriodic ( )
overridevirtual

Periodic callback for logging updates.

If a derived class needs to perform periodic updates to published values, override this method. It is intended to be called by the logging framework; this base class provides an empty implementation.

Reimplemented from valor::Loggable.

◆ positionSetter()

void valor::NeoController::positionSetter ( units::turn_t position,
int slot = 0 )
overridevirtual

Send the motor to a specific position.

Will use the motor's native trapezoidal motion profile to get the motor to that position. Can be tuned using the velocity and acceleration components of valor::PIDF via setPIDF

To be defined by the implemented BaseController class

Parameters
positionThe position to send the motor to

Implements valor::BaseController.

◆ powerSetter()

void valor::NeoController::powerSetter ( units::volt_t voltage)
overridevirtual

Reimplemented from valor::BaseController.

◆ reset()

void valor::NeoController::reset ( )
overridevirtual

Resets the motor and any state.

Clear the encoders for the motor and set to 0.

Additionally, should be called by the constructor to set default values before any logic is run.

To be defined by the implemented BaseController class

Implements valor::BaseController.

◆ setEncoderPosition()

void valor::NeoController::setEncoderPosition ( units::turn_t position)
overridevirtual

Implements valor::BaseController.

◆ setForwardLimit()

void valor::NeoController::setForwardLimit ( units::turn_t forward,
bool saveImmediately = false )
overridevirtual

Set the forward soft limit for the motor.

Soft limits restrict the reverse and forward direction to a certain range.

Parameters
forwardThe forward soft limit

Implements valor::BaseController.

◆ setGearRatios()

void valor::NeoController::setGearRatios ( double rotorToSensor,
double sensorToMech,
bool saveImmediately = false )
overridevirtual

Set the gear ratios for the motor.

Used to convert between the motor's rotor and the output shaft of the mechanism

To be defined by the implemented BaseController class

Parameters
rotorToSensorThe gear ratio from rotor to where the sensor is. Should be 1 if no external sensor
sensorToMechThe gear ratio from the sensor to the mechanism's output shaft. Should be the gear ratio if no external sensor
saveImmediatelyTell the underlying controller to apply the changes immediately, or to wait until a manual apply has been called

Implements valor::BaseController.

◆ setOpenLoopRamp()

void valor::NeoController::setOpenLoopRamp ( units::second_t time,
bool saveImmediately = false )
overridevirtual

Implements valor::BaseController.

◆ setPIDF()

void valor::NeoController::setPIDF ( valor::PIDF pidf,
int slot = 0,
bool saveImmediately = false )
overridevirtual

Change the PIDF values for the motor.

valor::PIDF has some default values already set and tested, but if the system requires some changes, use this method to change those defaults.

Parameters
pidfThe new PIDF values to use for the system
slotSet which slot of the motor to apply the PIDF. 0 if slots aren't compatible

Implements valor::BaseController.

◆ setReverseLimit()

void valor::NeoController::setReverseLimit ( units::turn_t reverse,
bool saveImmediately = false )
overridevirtual

Set the reverse soft limit for the motor.

Soft limits restrict the reverse and reverse direction to a certain range.

Parameters
reverseThe reverse soft limit

Implements valor::BaseController.

◆ setSimState()

void valor::NeoController::setSimState ( frc::sim::DCMotorSim & )
overridevirtual

Implements valor::BaseController.

◆ setupFollower()

void valor::NeoController::setupFollower ( int canID,
bool followerInverted = false )
overridevirtual

If a motor is paired with another motor, setup that other motor as a follower.

The follower motor will need a CAN ID, and then it will mimic and assume all other parameters of the lead motor

To be defined by the implemented BaseController class

Parameters
canIDThe CAN ID of the follower motor

Implements valor::BaseController.

◆ speedSetter()

void valor::NeoController::speedSetter ( units::turns_per_second_t speed,
int slot = 0 )
overridevirtual

Send the motor to a specific speed.

Will use the motor's native trapezoidal motion profile to get the motor to that position. Can be tuned using the PIDF components of valor::PIDF via setPIDF

To be defined by the implemented BaseController class

Parameters
speedThe speed to set the motor to

Implements valor::BaseController.


The documentation for this class was generated from the following file: