Initial commit - test serial

This commit is contained in:
Cole A. Deck
2024-03-24 22:20:00 -05:00
commit a4b1c1b7ed
273 changed files with 43716 additions and 0 deletions

View File

@ -0,0 +1,506 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/chassis/controller/chassisControllerIntegrated.hpp"
#include "okapi/api/chassis/controller/chassisControllerPid.hpp"
#include "okapi/api/chassis/controller/defaultOdomChassisController.hpp"
#include "okapi/api/chassis/model/hDriveModel.hpp"
#include "okapi/api/chassis/model/skidSteerModel.hpp"
#include "okapi/api/chassis/model/xDriveModel.hpp"
#include "okapi/api/util/logging.hpp"
#include "okapi/api/util/mathUtil.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include "okapi/impl/device/motor/motorGroup.hpp"
#include "okapi/impl/device/rotarysensor/adiEncoder.hpp"
#include "okapi/impl/device/rotarysensor/integratedEncoder.hpp"
#include "okapi/impl/device/rotarysensor/rotationSensor.hpp"
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
class ChassisControllerBuilder {
public:
/**
* A builder that creates ChassisControllers. Use this to create your ChassisController.
*
* @param ilogger The logger this instance will log to.
*/
explicit ChassisControllerBuilder(
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Sets the motors using a skid-steer layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const Motor &ileft, const Motor &iright);
/**
* Sets the motors using a skid-steer layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const MotorGroup &ileft, const MotorGroup &iright);
/**
* Sets the motors using a skid-steer layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const std::shared_ptr<AbstractMotor> &ileft,
const std::shared_ptr<AbstractMotor> &iright);
/**
* Sets the motors using an x-drive layout.
*
* @param itopLeft The top left motor.
* @param itopRight The top right motor.
* @param ibottomRight The bottom right motor.
* @param ibottomLeft The bottom left motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const Motor &itopLeft,
const Motor &itopRight,
const Motor &ibottomRight,
const Motor &ibottomLeft);
/**
* Sets the motors using an x-drive layout.
*
* @param itopLeft The top left motor.
* @param itopRight The top right motor.
* @param ibottomRight The bottom right motor.
* @param ibottomLeft The bottom left motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const MotorGroup &itopLeft,
const MotorGroup &itopRight,
const MotorGroup &ibottomRight,
const MotorGroup &ibottomLeft);
/**
* Sets the motors using an x-drive layout.
*
* @param itopLeft The top left motor.
* @param itopRight The top right motor.
* @param ibottomRight The bottom right motor.
* @param ibottomLeft The bottom left motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const std::shared_ptr<AbstractMotor> &itopLeft,
const std::shared_ptr<AbstractMotor> &itopRight,
const std::shared_ptr<AbstractMotor> &ibottomRight,
const std::shared_ptr<AbstractMotor> &ibottomLeft);
/**
* Sets the motors using an h-drive layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @param imiddle The middle motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withMotors(const Motor &ileft, const Motor &iright, const Motor &imiddle);
/**
* Sets the motors using an h-drive layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @param imiddle The middle motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withMotors(const MotorGroup &ileft, const MotorGroup &iright, const MotorGroup &imiddle);
/**
* Sets the motors using an h-drive layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @param imiddle The middle motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withMotors(const MotorGroup &ileft, const MotorGroup &iright, const Motor &imiddle);
/**
* Sets the motors using an h-drive layout.
*
* @param ileft The left motor.
* @param iright The right motor.
* @param imiddle The middle motor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMotors(const std::shared_ptr<AbstractMotor> &ileft,
const std::shared_ptr<AbstractMotor> &iright,
const std::shared_ptr<AbstractMotor> &imiddle);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const ADIEncoder &ileft, const ADIEncoder &iright);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @param imiddle The middle sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withSensors(const ADIEncoder &ileft, const ADIEncoder &iright, const ADIEncoder &imiddle);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const RotationSensor &ileft, const RotationSensor &iright);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @param imiddle The middle sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const RotationSensor &ileft,
const RotationSensor &iright,
const RotationSensor &imiddle);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const IntegratedEncoder &ileft,
const IntegratedEncoder &iright);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @param imiddle The middle sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const IntegratedEncoder &ileft,
const IntegratedEncoder &iright,
const ADIEncoder &imiddle);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const std::shared_ptr<ContinuousRotarySensor> &ileft,
const std::shared_ptr<ContinuousRotarySensor> &iright);
/**
* Sets the sensors. The default sensors are the motor's integrated encoders.
*
* @param ileft The left side sensor.
* @param iright The right side sensor.
* @param imiddle The middle sensor.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withSensors(const std::shared_ptr<ContinuousRotarySensor> &ileft,
const std::shared_ptr<ContinuousRotarySensor> &iright,
const std::shared_ptr<ContinuousRotarySensor> &imiddle);
/**
* Sets the PID controller gains, causing the builder to generate a ChassisControllerPID. Uses the
* turn controller's gains for the angle controller's gains.
*
* @param idistanceGains The distance controller's gains.
* @param iturnGains The turn controller's gains.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withGains(const IterativePosPIDController::Gains &idistanceGains,
const IterativePosPIDController::Gains &iturnGains);
/**
* Sets the PID controller gains, causing the builder to generate a ChassisControllerPID.
*
* @param idistanceGains The distance controller's gains.
* @param iturnGains The turn controller's gains.
* @param iangleGains The angle controller's gains.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withGains(const IterativePosPIDController::Gains &idistanceGains,
const IterativePosPIDController::Gains &iturnGains,
const IterativePosPIDController::Gains &iangleGains);
/**
* Sets the odometry information, causing the builder to generate an Odometry variant.
*
* @param imode The new default StateMode used to interpret target points and query the Odometry
* state.
* @param imoveThreshold The minimum length movement.
* @param iturnThreshold The minimum angle turn.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withOdometry(const StateMode &imode = StateMode::FRAME_TRANSFORMATION,
const QLength &imoveThreshold = 0_mm,
const QAngle &iturnThreshold = 0_deg);
/**
* Sets the odometry information, causing the builder to generate an Odometry variant.
*
* @param iodomScales The ChassisScales used just for odometry (if they are different than those
* for the drive).
* @param imode The new default StateMode used to interpret target points and query the Odometry
* state.
* @param imoveThreshold The minimum length movement.
* @param iturnThreshold The minimum angle turn.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withOdometry(const ChassisScales &iodomScales,
const StateMode &imode = StateMode::FRAME_TRANSFORMATION,
const QLength &imoveThreshold = 0_mm,
const QAngle &iturnThreshold = 0_deg);
/**
* Sets the odometry information, causing the builder to generate an Odometry variant.
*
* @param iodometry The odometry object.
* @param imode The new default StateMode used to interpret target points and query the Odometry
* state.
* @param imoveThreshold The minimum length movement.
* @param iturnThreshold The minimum angle turn.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withOdometry(std::shared_ptr<Odometry> iodometry,
const StateMode &imode = StateMode::FRAME_TRANSFORMATION,
const QLength &imoveThreshold = 0_mm,
const QAngle &iturnThreshold = 0_deg);
/**
* Sets the derivative filters. Uses a PassthroughFilter by default.
*
* @param idistanceFilter The distance controller's filter.
* @param iturnFilter The turn controller's filter.
* @param iangleFilter The angle controller's filter.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withDerivativeFilters(
std::unique_ptr<Filter> idistanceFilter,
std::unique_ptr<Filter> iturnFilter = std::make_unique<PassthroughFilter>(),
std::unique_ptr<Filter> iangleFilter = std::make_unique<PassthroughFilter>());
/**
* Sets the chassis dimensions.
*
* @param igearset The gearset in the drive motors.
* @param iscales The ChassisScales for the base.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withDimensions(const AbstractMotor::GearsetRatioPair &igearset,
const ChassisScales &iscales);
/**
* Sets the max velocity. Overrides the max velocity of the gearset.
*
* @param imaxVelocity The max velocity.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMaxVelocity(double imaxVelocity);
/**
* Sets the max voltage. The default is `12000`.
*
* @param imaxVoltage The max voltage.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withMaxVoltage(double imaxVoltage);
/**
* Sets the TimeUtilFactory used when building a ChassisController. This instance will be given
* to the ChassisController (not to controllers it uses). The default is the static
* TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withChassisControllerTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Sets the TimeUtilFactory used when building a ClosedLoopController. This instance will be given
* to any ClosedLoopController instances. The default is the static TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
ChassisControllerBuilder &
withClosedLoopControllerTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Creates a new ConfigurableTimeUtilFactory with the given parameters. Given to any
* ClosedLoopController instances.
*
* @param iatTargetError The minimum error to be considered settled.
* @param iatTargetDerivative The minimum error derivative to be considered settled.
* @param iatTargetTime The minimum time within atTargetError to be considered settled.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withClosedLoopControllerTimeUtil(double iatTargetError = 50,
double iatTargetDerivative = 5,
const QTime &iatTargetTime = 250_ms);
/**
* Sets the TimeUtilFactory used when building an Odometry. The default is the static
* TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withOdometryTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Sets the logger used for the ChassisController and ClosedLoopControllers.
*
* @param ilogger The logger.
* @return An ongoing builder.
*/
ChassisControllerBuilder &withLogger(const std::shared_ptr<Logger> &ilogger);
/**
* Parents the internal tasks started by this builder to the current task, meaning they will be
* deleted once the current task is deleted. The `initialize` and `competition_initialize` tasks
* are never parented to. This is the default behavior.
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
ChassisControllerBuilder &parentedToCurrentTask();
/**
* Prevents parenting the internal tasks started by this builder to the current task, meaning they
* will not be deleted once the current task is deleted. This can cause runaway tasks, but is
* sometimes the desired behavior (e.x., if you want to use this builder once in `autonomous` and
* then again in `opcontrol`).
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
ChassisControllerBuilder &notParentedToCurrentTask();
/**
* Builds the ChassisController. Throws a std::runtime_exception if no motors were set or if no
* dimensions were set.
*
* @return A fully built ChassisController.
*/
std::shared_ptr<ChassisController> build();
/**
* Builds the OdomChassisController. Throws a std::runtime_exception if no motors were set, if no
* dimensions were set, or if no odometry information was passed.
*
* @return A fully built OdomChassisController.
*/
std::shared_ptr<OdomChassisController> buildOdometry();
private:
std::shared_ptr<Logger> logger;
struct SkidSteerMotors {
std::shared_ptr<AbstractMotor> left;
std::shared_ptr<AbstractMotor> right;
};
struct XDriveMotors {
std::shared_ptr<AbstractMotor> topLeft;
std::shared_ptr<AbstractMotor> topRight;
std::shared_ptr<AbstractMotor> bottomRight;
std::shared_ptr<AbstractMotor> bottomLeft;
};
struct HDriveMotors {
std::shared_ptr<AbstractMotor> left;
std::shared_ptr<AbstractMotor> right;
std::shared_ptr<AbstractMotor> middle;
};
enum class DriveMode { SkidSteer, XDrive, HDrive };
bool hasMotors{false}; // Used to verify motors were passed
DriveMode driveMode{DriveMode::SkidSteer};
SkidSteerMotors skidSteerMotors;
XDriveMotors xDriveMotors;
HDriveMotors hDriveMotors;
bool sensorsSetByUser{false}; // Used so motors don't overwrite sensors set manually
std::shared_ptr<ContinuousRotarySensor> leftSensor{nullptr};
std::shared_ptr<ContinuousRotarySensor> rightSensor{nullptr};
std::shared_ptr<ContinuousRotarySensor> middleSensor{nullptr};
bool hasGains{false}; // Whether gains were passed, no gains means CCI
IterativePosPIDController::Gains distanceGains;
std::unique_ptr<Filter> distanceFilter = std::make_unique<PassthroughFilter>();
IterativePosPIDController::Gains angleGains;
std::unique_ptr<Filter> angleFilter = std::make_unique<PassthroughFilter>();
IterativePosPIDController::Gains turnGains;
std::unique_ptr<Filter> turnFilter = std::make_unique<PassthroughFilter>();
TimeUtilFactory chassisControllerTimeUtilFactory = TimeUtilFactory();
TimeUtilFactory closedLoopControllerTimeUtilFactory = TimeUtilFactory();
TimeUtilFactory odometryTimeUtilFactory = TimeUtilFactory();
AbstractMotor::GearsetRatioPair gearset{AbstractMotor::gearset::invalid, 1.0};
ChassisScales driveScales{{1, 1}, imev5GreenTPR};
bool differentOdomScales{false};
ChassisScales odomScales{{1, 1}, imev5GreenTPR};
std::shared_ptr<Logger> controllerLogger = Logger::getDefaultLogger();
bool hasOdom{false}; // Whether odometry was passed
std::shared_ptr<Odometry> odometry;
StateMode stateMode;
QLength moveThreshold;
QAngle turnThreshold;
bool maxVelSetByUser{false}; // Used so motors don't overwrite maxVelocity
double maxVelocity{600};
double maxVoltage{12000};
bool isParentedToCurrentTask{true};
std::shared_ptr<ChassisControllerPID> buildCCPID();
std::shared_ptr<ChassisControllerIntegrated> buildCCI();
std::shared_ptr<DefaultOdomChassisController>
buildDOCC(std::shared_ptr<ChassisController> chassisController);
std::shared_ptr<ChassisModel> makeChassisModel();
std::shared_ptr<SkidSteerModel> makeSkidSteerModel();
std::shared_ptr<XDriveModel> makeXDriveModel();
std::shared_ptr<HDriveModel> makeHDriveModel();
};
} // namespace okapi

View File

@ -0,0 +1,177 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/chassis/controller/chassisController.hpp"
#include "okapi/api/control/async/asyncLinearMotionProfileController.hpp"
#include "okapi/api/control/async/asyncMotionProfileController.hpp"
#include "okapi/api/util/logging.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include "okapi/impl/device/motor/motorGroup.hpp"
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
class AsyncMotionProfileControllerBuilder {
public:
/**
* A builder that creates async motion profile controllers. Use this to build an
* AsyncMotionProfileController or an AsyncLinearMotionProfileController.
*
* @param ilogger The logger this instance will log to.
*/
explicit AsyncMotionProfileControllerBuilder(
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Sets the output. This must be used with buildLinearMotionProfileController().
*
* @param ioutput The output.
* @param idiameter The diameter of the mechanical part the motor spins.
* @param ipair The gearset.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withOutput(const Motor &ioutput,
const QLength &idiameter,
const AbstractMotor::GearsetRatioPair &ipair);
/**
* Sets the output. This must be used with buildLinearMotionProfileController().
*
* @param ioutput The output.
* @param idiameter The diameter of the mechanical part the motor spins.
* @param ipair The gearset.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withOutput(const MotorGroup &ioutput,
const QLength &idiameter,
const AbstractMotor::GearsetRatioPair &ipair);
/**
* Sets the output. This must be used with buildLinearMotionProfileController().
*
* @param ioutput The output.
* @param idiameter The diameter of the mechanical part the motor spins.
* @param ipair The gearset.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &
withOutput(const std::shared_ptr<ControllerOutput<double>> &ioutput,
const QLength &idiameter,
const AbstractMotor::GearsetRatioPair &ipair);
/**
* Sets the output. This must be used with buildMotionProfileController().
*
* @param icontroller The chassis controller to use.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withOutput(ChassisController &icontroller);
/**
* Sets the output. This must be used with buildMotionProfileController().
*
* @param icontroller The chassis controller to use.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &
withOutput(const std::shared_ptr<ChassisController> &icontroller);
/**
* Sets the output. This must be used with buildMotionProfileController().
*
* @param imodel The chassis model to use.
* @param iscales The chassis dimensions.
* @param ipair The gearset.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withOutput(const std::shared_ptr<ChassisModel> &imodel,
const ChassisScales &iscales,
const AbstractMotor::GearsetRatioPair &ipair);
/**
* Sets the limits.
*
* @param ilimits The limits.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withLimits(const PathfinderLimits &ilimits);
/**
* Sets the TimeUtilFactory used when building the controller. The default is the static
* TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Sets the logger.
*
* @param ilogger The logger.
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &withLogger(const std::shared_ptr<Logger> &ilogger);
/**
* Parents the internal tasks started by this builder to the current task, meaning they will be
* deleted once the current task is deleted. The `initialize` and `competition_initialize` tasks
* are never parented to. This is the default behavior.
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &parentedToCurrentTask();
/**
* Prevents parenting the internal tasks started by this builder to the current task, meaning they
* will not be deleted once the current task is deleted. This can cause runaway tasks, but is
* sometimes the desired behavior (e.x., if you want to use this builder once in `autonomous` and
* then again in `opcontrol`).
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncMotionProfileControllerBuilder &notParentedToCurrentTask();
/**
* Builds the AsyncLinearMotionProfileController.
*
* @return A fully built AsyncLinearMotionProfileController.
*/
std::shared_ptr<AsyncLinearMotionProfileController> buildLinearMotionProfileController();
/**
* Builds the AsyncMotionProfileController.
*
* @return A fully built AsyncMotionProfileController.
*/
std::shared_ptr<AsyncMotionProfileController> buildMotionProfileController();
private:
std::shared_ptr<Logger> logger;
bool hasLimits{false};
PathfinderLimits limits;
bool hasOutput{false};
std::shared_ptr<ControllerOutput<double>> output;
QLength diameter;
bool hasModel{false};
std::shared_ptr<ChassisModel> model;
ChassisScales scales{{1, 1}, imev5GreenTPR};
AbstractMotor::GearsetRatioPair pair{AbstractMotor::gearset::invalid};
TimeUtilFactory timeUtilFactory = TimeUtilFactory();
std::shared_ptr<Logger> controllerLogger = Logger::getDefaultLogger();
bool isParentedToCurrentTask{true};
};
} // namespace okapi

View File

@ -0,0 +1,190 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/control/async/asyncPosIntegratedController.hpp"
#include "okapi/api/control/async/asyncPosPidController.hpp"
#include "okapi/api/control/async/asyncPositionController.hpp"
#include "okapi/api/util/logging.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include "okapi/impl/device/motor/motorGroup.hpp"
#include "okapi/impl/device/rotarysensor/adiEncoder.hpp"
#include "okapi/impl/device/rotarysensor/integratedEncoder.hpp"
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
class AsyncPosControllerBuilder {
public:
/**
* A builder that creates async position controllers. Use this to create an
* AsyncPosIntegratedController or an AsyncPosPIDController.
*
* @param ilogger The logger this instance will log to.
*/
explicit AsyncPosControllerBuilder(
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withMotor(const Motor &imotor);
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withMotor(const MotorGroup &imotor);
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withMotor(const std::shared_ptr<AbstractMotor> &imotor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withSensor(const ADIEncoder &isensor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withSensor(const IntegratedEncoder &isensor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withSensor(const std::shared_ptr<RotarySensor> &isensor);
/**
* Sets the controller gains, causing the builder to generate an AsyncPosPIDController. This does
* not set the integrated control's gains.
*
* @param igains The gains.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withGains(const IterativePosPIDController::Gains &igains);
/**
* Sets the derivative filter which filters the derivative term before it is scaled by kD. The
* filter is ignored when using integrated control. The default derivative filter is a
* PassthroughFilter.
*
* @param iderivativeFilter The derivative filter.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withDerivativeFilter(std::unique_ptr<Filter> iderivativeFilter);
/**
* Sets the gearset. The default gearset is derived from the motor's.
*
* @param igearset The gearset.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withGearset(const AbstractMotor::GearsetRatioPair &igearset);
/**
* Sets the maximum velocity. The default maximum velocity is derived from the motor's gearset.
* This parameter is ignored when using an AsyncPosPIDController.
*
* @param imaxVelocity The maximum velocity.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withMaxVelocity(double imaxVelocity);
/**
* Sets the TimeUtilFactory used when building the controller. The default is the static
* TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Sets the logger.
*
* @param ilogger The logger.
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &withLogger(const std::shared_ptr<Logger> &ilogger);
/**
* Parents the internal tasks started by this builder to the current task, meaning they will be
* deleted once the current task is deleted. The `initialize` and `competition_initialize` tasks
* are never parented to. This is the default behavior.
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &parentedToCurrentTask();
/**
* Prevents parenting the internal tasks started by this builder to the current task, meaning they
* will not be deleted once the current task is deleted. This can cause runaway tasks, but is
* sometimes the desired behavior (e.x., if you want to use this builder once in `autonomous` and
* then again in `opcontrol`).
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncPosControllerBuilder &notParentedToCurrentTask();
/**
* Builds the AsyncPositionController. Throws a std::runtime_exception is no motors were set.
*
* @return A fully built AsyncPositionController.
*/
std::shared_ptr<AsyncPositionController<double, double>> build();
private:
std::shared_ptr<Logger> logger;
bool hasMotors{false}; // Used to verify motors were passed
std::shared_ptr<AbstractMotor> motor;
bool sensorsSetByUser{false}; // Used so motors don't overwrite sensors set manually
std::shared_ptr<RotarySensor> sensor;
bool hasGains{false}; // Whether gains were passed, no gains means integrated control
IterativePosPIDController::Gains gains;
std::unique_ptr<Filter> derivativeFilter = std::make_unique<PassthroughFilter>();
bool gearsetSetByUser{false}; // Used so motor's don't overwrite a gearset set manually
AbstractMotor::GearsetRatioPair pair{AbstractMotor::gearset::invalid};
bool maxVelSetByUser{false}; // Used so motors don't overwrite maxVelocity
double maxVelocity{600};
TimeUtilFactory timeUtilFactory = TimeUtilFactory();
std::shared_ptr<Logger> controllerLogger = Logger::getDefaultLogger();
bool isParentedToCurrentTask{true};
std::shared_ptr<AsyncPosIntegratedController> buildAPIC();
std::shared_ptr<AsyncPosPIDController> buildAPPC();
};
} // namespace okapi

View File

@ -0,0 +1,203 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/control/async/asyncVelIntegratedController.hpp"
#include "okapi/api/control/async/asyncVelPidController.hpp"
#include "okapi/api/control/async/asyncVelocityController.hpp"
#include "okapi/api/util/logging.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include "okapi/impl/device/motor/motorGroup.hpp"
#include "okapi/impl/device/rotarysensor/adiEncoder.hpp"
#include "okapi/impl/device/rotarysensor/integratedEncoder.hpp"
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
class AsyncVelControllerBuilder {
public:
/**
* A builder that creates async velocity controllers. Use this to create an
* AsyncVelIntegratedController or an AsyncVelPIDController.
*
* @param ilogger The logger this instance will log to.
*/
explicit AsyncVelControllerBuilder(
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withMotor(const Motor &imotor);
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withMotor(const MotorGroup &imotor);
/**
* Sets the motor.
*
* @param imotor The motor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withMotor(const std::shared_ptr<AbstractMotor> &imotor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withSensor(const ADIEncoder &isensor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withSensor(const IntegratedEncoder &isensor);
/**
* Sets the sensor. The default sensor is the motor's integrated encoder.
*
* @param isensor The sensor.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withSensor(const std::shared_ptr<RotarySensor> &isensor);
/**
* Sets the controller gains, causing the builder to generate an AsyncVelPIDController. This does
* not set the integrated control's gains.
*
* @param igains The gains.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withGains(const IterativeVelPIDController::Gains &igains);
/**
* Sets the VelMath which calculates and filters velocity. This is ignored when using integrated
* controller. If using a PID controller (by setting the gains), this is required.
*
* @param ivelMath The VelMath.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withVelMath(std::unique_ptr<VelMath> ivelMath);
/**
* Sets the derivative filter which filters the derivative term before it is scaled by kD. The
* filter is ignored when using integrated control. The default derivative filter is a
* PassthroughFilter.
*
* @param iderivativeFilter The derivative filter.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withDerivativeFilter(std::unique_ptr<Filter> iderivativeFilter);
/**
* Sets the gearset. The default gearset is derived from the motor's.
*
* @param igearset The gearset.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withGearset(const AbstractMotor::GearsetRatioPair &igearset);
/**
* Sets the maximum velocity. The default maximum velocity is derived from the motor's gearset.
* This parameter is ignored when using an AsyncVelPIDController.
*
* @param imaxVelocity The maximum velocity.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withMaxVelocity(double imaxVelocity);
/**
* Sets the TimeUtilFactory used when building the controller. The default is the static
* TimeUtilFactory.
*
* @param itimeUtilFactory The TimeUtilFactory.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withTimeUtilFactory(const TimeUtilFactory &itimeUtilFactory);
/**
* Sets the logger.
*
* @param ilogger The logger.
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &withLogger(const std::shared_ptr<Logger> &ilogger);
/**
* Parents the internal tasks started by this builder to the current task, meaning they will be
* deleted once the current task is deleted. The `initialize` and `competition_initialize` tasks
* are never parented to. This is the default behavior.
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &parentedToCurrentTask();
/**
* Prevents parenting the internal tasks started by this builder to the current task, meaning they
* will not be deleted once the current task is deleted. This can cause runaway tasks, but is
* sometimes the desired behavior (e.x., if you want to use this builder once in `autonomous` and
* then again in `opcontrol`).
*
* Read more about this in the [builders and tasks tutorial]
* (docs/tutorials/concepts/builders-and-tasks.md).
*
* @return An ongoing builder.
*/
AsyncVelControllerBuilder &notParentedToCurrentTask();
/**
* Builds the AsyncVelocityController. Throws a std::runtime_exception is no motors were set.
*
* @return A fully built AsyncVelocityController.
*/
std::shared_ptr<AsyncVelocityController<double, double>> build();
private:
std::shared_ptr<Logger> logger;
bool hasMotors{false}; // Used to verify motors were passed
std::shared_ptr<AbstractMotor> motor;
bool sensorsSetByUser{false}; // Used so motors don't overwrite sensors set manually
std::shared_ptr<RotarySensor> sensor;
bool hasGains{false}; // Whether gains were passed, no gains means integrated control
IterativeVelPIDController::Gains gains;
bool hasVelMath{false}; // Used to verify velMath was passed
std::unique_ptr<VelMath> velMath;
std::unique_ptr<Filter> derivativeFilter = std::make_unique<PassthroughFilter>();
bool gearsetSetByUser{false}; // Used so motor's don't overwrite a gearset set manually
AbstractMotor::GearsetRatioPair pair{AbstractMotor::gearset::invalid};
bool maxVelSetByUser{false}; // Used so motors don't overwrite maxVelocity
double maxVelocity{600};
TimeUtilFactory timeUtilFactory = TimeUtilFactory();
std::shared_ptr<Logger> controllerLogger = Logger::getDefaultLogger();
bool isParentedToCurrentTask{true};
std::shared_ptr<AsyncVelIntegratedController> buildAVIC();
std::shared_ptr<AsyncVelPIDController> buildAVPC();
};
} // namespace okapi

View File

@ -0,0 +1,120 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/control/iterative/iterativeMotorVelocityController.hpp"
#include "okapi/api/control/iterative/iterativePosPidController.hpp"
#include "okapi/api/control/iterative/iterativeVelPidController.hpp"
#include "okapi/api/util/mathUtil.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include "okapi/impl/device/motor/motorGroup.hpp"
#include "okapi/impl/filter/velMathFactory.hpp"
namespace okapi {
class IterativeControllerFactory {
public:
/**
* Position PID controller.
*
* @param ikP proportional gain
* @param ikI integral gain
* @param ikD derivative gain
* @param ikBias controller bias (constant offset added to the output)
* @param iderivativeFilter A filter for filtering the derivative term.
* @param ilogger The logger this instance will log to.
*/
static IterativePosPIDController
posPID(double ikP,
double ikI,
double ikD,
double ikBias = 0,
std::unique_ptr<Filter> iderivativeFilter = std::make_unique<PassthroughFilter>(),
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity PD controller.
*
* @param ikP proportional gain
* @param ikD derivative gain
* @param ikF feed-forward gain
* @param ikSF a feed-forward gain to counteract static friction
* @param iderivativeFilter A filter for filtering the derivative term.
* @param ilogger The logger this instance will log to.
*/
static IterativeVelPIDController
velPID(double ikP,
double ikD,
double ikF = 0,
double ikSF = 0,
std::unique_ptr<VelMath> ivelMath = VelMathFactory::createPtr(imev5GreenTPR),
std::unique_ptr<Filter> iderivativeFilter = std::make_unique<PassthroughFilter>(),
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity PD controller that automatically writes to the motor.
*
* @param imotor output motor
* @param ikP proportional gain
* @param ikD derivative gain
* @param ikF feed-forward gain
* @param ikSF a feed-forward gain to counteract static friction
* @param ivelMath The VelMath.
* @param iderivativeFilter A filter for filtering the derivative term.
* @param ilogger The logger this instance will log to.
*/
static IterativeMotorVelocityController
motorVelocity(Motor imotor,
double ikP,
double ikD,
double ikF = 0,
double ikSF = 0,
std::unique_ptr<VelMath> ivelMath = VelMathFactory::createPtr(imev5GreenTPR),
std::unique_ptr<Filter> iderivativeFilter = std::make_unique<PassthroughFilter>(),
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity PD controller that automatically writes to the motor.
*
* @param imotor output motor
* @param ikP proportional gain
* @param ikD derivative gain
* @param ikF feed-forward gain
* @param ikSF a feed-forward gain to counteract static friction
* @param ivelMath The VelMath.
* @param iderivativeFilter A filter for filtering the derivative term.
* @param ilogger The logger this instance will log to.
*/
static IterativeMotorVelocityController
motorVelocity(MotorGroup imotor,
double ikP,
double ikD,
double ikF = 0,
double ikSF = 0,
std::unique_ptr<VelMath> ivelMath = VelMathFactory::createPtr(imev5GreenTPR),
std::unique_ptr<Filter> iderivativeFilter = std::make_unique<PassthroughFilter>(),
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity PD controller that automatically writes to the motor.
*
* @param imotor output motor
* @param icontroller controller to use
*/
static IterativeMotorVelocityController
motorVelocity(Motor imotor,
std::shared_ptr<IterativeVelocityController<double, double>> icontroller);
/**
* Velocity PD controller that automatically writes to the motor.
*
* @param imotor output motor
* @param icontroller controller to use
*/
static IterativeMotorVelocityController
motorVelocity(MotorGroup imotor,
std::shared_ptr<IterativeVelocityController<double, double>> icontroller);
};
} // namespace okapi

View File

@ -0,0 +1,25 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/control/util/controllerRunner.hpp"
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
template <typename Input, typename Output> class ControllerRunnerFactory {
public:
/**
* A utility class that runs a closed-loop controller.
*
* @param ilogger The logger this instance will log to.
* @return
*/
static ControllerRunner<Input, Output>
create(const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger()) {
return ControllerRunner<Input, Output>(TimeUtilFactory::createDefault(), ilogger);
}
};
} // namespace okapi

View File

@ -0,0 +1,47 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/control/util/pidTuner.hpp"
#include <memory>
namespace okapi {
class PIDTunerFactory {
public:
static PIDTuner create(const std::shared_ptr<ControllerInput<double>> &iinput,
const std::shared_ptr<ControllerOutput<double>> &ioutput,
QTime itimeout,
std::int32_t igoal,
double ikPMin,
double ikPMax,
double ikIMin,
double ikIMax,
double ikDMin,
double ikDMax,
std::int32_t inumIterations = 5,
std::int32_t inumParticles = 16,
double ikSettle = 1,
double ikITAE = 2,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
static std::unique_ptr<PIDTuner>
createPtr(const std::shared_ptr<ControllerInput<double>> &iinput,
const std::shared_ptr<ControllerOutput<double>> &ioutput,
QTime itimeout,
std::int32_t igoal,
double ikPMin,
double ikPMax,
double ikIMin,
double ikIMax,
double ikDMin,
double ikDMax,
std::int32_t inumIterations = 5,
std::int32_t inumParticles = 16,
double ikSettle = 1,
double ikITAE = 2,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
};
} // namespace okapi

View File

@ -0,0 +1,71 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerInput.hpp"
#include "okapi/api/filter/passthroughFilter.hpp"
#include <memory>
namespace okapi {
class ADIUltrasonic : public ControllerInput<double> {
public:
/**
* An ultrasonic sensor in the ADI (3-wire) ports.
*
* ```cpp
* auto ultra = ADIUltrasonic('A', 'B');
* auto filteredUltra = ADIUltrasonic('A', 'B', std::make_unique<MedianFilter<5>>());
* ```
*
* @param iportPing The port connected to the orange OUTPUT cable. This must be in port ``1``,
* ``3``, ``5``, or ``7`` (``A``, ``C``, ``E``, or ``G``).
* @param iportEcho The port connected to the yellow INPUT cable. This must be in the next highest
* port following iportPing.
* @param ifilter The filter to use for filtering the distance measurements.
*/
ADIUltrasonic(std::uint8_t iportPing,
std::uint8_t iportEcho,
std::unique_ptr<Filter> ifilter = std::make_unique<PassthroughFilter>());
/**
* An ultrasonic sensor in the ADI (3-wire) ports.
*
* ```cpp
* auto ultra = ADIUltrasonic({1, 'A', 'B'});
* auto filteredUltra = ADIUltrasonic({1, 'A', 'B'}, std::make_unique<MedianFilter<5>>());
* ```
*
* @param iports The ports the ultrasonic is plugged in to in the order ``{smart port, ping port,
* echo port}``. The smart port is the smart port number (``[1, 21]``). The ping port is the port
* connected to the orange OUTPUT cable. This must be in port ``1``, ``3``, ``5``, or ``7``
* (``A``, ``C``, ``E``, or ``G``). The echo port is the port connected to the yellow INPUT cable.
* This must be in the next highest port following the ping port.
* @param ifilter The filter to use for filtering the distance measurements.
*/
ADIUltrasonic(std::tuple<std::uint8_t, std::uint8_t, std::uint8_t> iports,
std::unique_ptr<Filter> ifilter = std::make_unique<PassthroughFilter>());
virtual ~ADIUltrasonic();
/**
* Returns the current filtered sensor value.
*
* @return current value
*/
virtual double get();
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller. Calls get().
*/
virtual double controllerGet() override;
protected:
pros::c::ext_adi_ultrasonic_t ultra;
std::unique_ptr<Filter> filter;
};
} // namespace okapi

View File

@ -0,0 +1,50 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/button/buttonBase.hpp"
namespace okapi {
class ADIButton : public ButtonBase {
public:
/**
* A button in an ADI port.
*
* ```cpp
* auto btn = ADIButton('A', false);
* auto invertedBtn = ADIButton('A', true);
* ```
*
* @param iport The ADI port number (``[1, 8]``, ``[a, h]``, ``[A, H]``).
* @param iinverted Whether the button is inverted (``true`` meaning default pressed and ``false``
* meaning default not pressed).
*/
ADIButton(std::uint8_t iport, bool iinverted = false);
/**
* A button in an ADI port.
*
* ```cpp
* auto btn = ADIButton({1, 'A'}, false);
* auto invertedBtn = ADIButton({1, 'A'}, true);
* ```
*
* @param iports The ports the button is plugged in to in the order ``{smart port, button port}``.
* The smart port is the smart port number (``[1, 21]``). The button port is the ADI port number
* (``[1, 8]``, ``[a, h]``, ``[A, H]``).
* @param iinverted Whether the button is inverted (``true`` meaning default pressed and ``false``
* meaning default not pressed).
*/
ADIButton(std::pair<std::uint8_t, std::uint8_t> iports, bool iinverted = false);
protected:
std::uint8_t smartPort;
std::uint8_t port;
virtual bool currentlyPressed() override;
};
} // namespace okapi

View File

@ -0,0 +1,38 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/button/buttonBase.hpp"
#include "okapi/impl/device/controllerUtil.hpp"
namespace okapi {
class ControllerButton : public ButtonBase {
public:
/**
* A button on a Controller.
*
* @param ibtn The button id.
* @param iinverted Whether the button is inverted (default pressed instead of default released).
*/
ControllerButton(ControllerDigital ibtn, bool iinverted = false);
/**
* A button on a Controller.
*
* @param icontroller The Controller the button is on.
* @param ibtn The button id.
* @param iinverted Whether the button is inverted (default pressed instead of default released).
*/
ControllerButton(ControllerId icontroller, ControllerDigital ibtn, bool iinverted = false);
protected:
pros::controller_id_e_t id;
pros::controller_digital_e_t btn;
virtual bool currentlyPressed() override;
};
} // namespace okapi

View File

@ -0,0 +1,118 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/impl/device/button/controllerButton.hpp"
#include "okapi/impl/device/controllerUtil.hpp"
#include <array>
namespace okapi {
class Controller {
public:
Controller(ControllerId iid = ControllerId::master);
virtual ~Controller();
/**
* Returns whether the controller is connected.
*
* @return true if the controller is connected
*/
virtual bool isConnected();
/**
* Returns the current analog reading for the channel in the range [-1, 1]. Returns 0 if the
* controller is not connected.
*
* @param ichannel the channel to read
* @return the value of that channel in the range [-1, 1]
*/
virtual float getAnalog(ControllerAnalog ichannel);
/**
* Returns whether the digital button is currently pressed. Returns false if the controller is
* not connected.
*
* @param ibutton the button to check
* @return true if the button is pressed, false if the controller is not connected
*/
virtual bool getDigital(ControllerDigital ibutton);
/**
* Returns a ControllerButton for the given button on this controller.
*
* @param ibtn the button
* @return a ControllerButton on this controller
*/
virtual ControllerButton &operator[](ControllerDigital ibtn);
/**
* Sets text to the controller LCD screen.
*
* @param iline the line number in the range [0-2] at which the text will be displayed
* @param icol the column number in the range [0-14] at which the text will be displayed
* @param itext the string to display
* @return 1 if the operation was successful, PROS_ERR otherwise
*/
virtual std::int32_t setText(std::uint8_t iline, std::uint8_t icol, std::string itext);
/**
* Clears all of the lines of the controller screen. On vexOS version 1.0.0 this function will
* block for 110ms.
*
* @return 1 if the operation was successful, PROS_ERR otherwise
*/
virtual std::int32_t clear();
/**
* Clears an individual line of the controller screen.
*
* @param iline the line number to clear in the range [0, 2].
* @return 1 if the operation was successful, PROS_ERR otherwise
*/
virtual std::int32_t clearLine(std::uint8_t iline);
/**
* Rumble the controller.
*
* Controller rumble activation is currently in beta, so continuous, fast
* updates will not work well.
*
* @param irumblePattern A string consisting of the characters '.', '-', and ' ', where dots are
* short rumbles, dashes are long rumbles, and spaces are pauses. Maximum supported length is 8
* characters.
*
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t rumble(std::string irumblePattern);
/**
* Gets the battery capacity of the given controller.
*
* This function uses the following values of errno when an error state is reached:
* EACCES - Another resource is currently trying to access the controller port.
*
* @return the controller's battery capacity
*/
virtual std::int32_t getBatteryCapacity();
/**
* Gets the battery level of the given controller.
*
* This function uses the following values of errno when an error state is reached:
* EACCES - Another resource is currently trying to access the controller port.
*
* @return the controller's battery level
*/
virtual std::int32_t getBatteryLevel();
protected:
ControllerId okapiId;
pros::controller_id_e_t prosId;
std::array<ControllerButton *, 12> buttonArray{};
};
} // namespace okapi

View File

@ -0,0 +1,64 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
namespace okapi {
/**
* Which controller role this has.
*/
enum class ControllerId {
master = 0, ///< master
partner = 1 ///< partner
};
/**
* The analog sticks.
*/
enum class ControllerAnalog {
leftX = 0, ///< leftX
leftY = 1, ///< leftY
rightX = 2, ///< rightX
rightY = 3 ///< rightY
};
/**
* Various buttons.
*/
enum class ControllerDigital {
L1 = 6, ///< L1
L2 = 7, ///< L2
R1 = 8, ///< R1
R2 = 9, ///< R2
up = 10, ///< up
down = 11, ///< down
left = 12, ///< left
right = 13, ///< right
X = 14, ///< X
B = 15, ///< B
Y = 16, ///< Y
A = 17 ///< A
};
class ControllerUtil {
public:
/**
* Maps an `id` to the PROS enum equivalent.
*/
static pros::controller_id_e_t idToProsEnum(ControllerId in);
/**
* Maps an `analog` to the PROS enum equivalent.
*/
static pros::controller_analog_e_t analogToProsEnum(ControllerAnalog in);
/**
* Maps a `digital` to the PROS enum equivalent.
*/
static pros::controller_digital_e_t digitalToProsEnum(ControllerDigital in);
};
} // namespace okapi

View File

@ -0,0 +1,76 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerInput.hpp"
#include "okapi/api/filter/passthroughFilter.hpp"
#include <memory>
namespace okapi {
class DistanceSensor : public ControllerInput<double> {
public:
/**
* A distance sensor on a V5 port.
*
* ```cpp
* auto ds = DistanceSensor(1);
* auto filteredDistSensor = DistanceSensor(1, std::make_unique<MedianFilter<5>>());
* ```
*
* @param iport The V5 port the device uses.
* @param ifilter The filter to use for filtering the distance measurements.
*/
DistanceSensor(std::uint8_t iport,
std::unique_ptr<Filter> ifilter = std::make_unique<PassthroughFilter>());
virtual ~DistanceSensor() = default;
/**
* Get the current filtered sensor value in mm.
*
* @return The current filtered sensor value in mm.
*/
double get();
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return The same as [get](@ref okapi::DistanceSensor::get).
*/
double controllerGet() override;
/**
* Get the confidence in the distance reading. This value has a range of ``[0, 63]``. ``63`` means
* high confidence, lower values imply less confidence. Confidence is only available when distance
* is greater than ``200`` mm.
*
* @return The confidence value in the range ``[0, 63]``.
*/
std::int32_t getConfidence() const;
/**
* Get the current guess at relative object size. This value has a range of ``[0, 400]``. A 18" x
* 30" grey card will return a value of approximately ``75`` in typical room lighting.
*
* @return The size value in the range ``[0, 400]`` or ``PROS_ERR`` if the operation failed,
* setting errno.
*/
std::int32_t getObjectSize() const;
/**
* Get the object velocity in m/s.
*
* @return The object velocity in m/s.
*/
double getObjectVelocity() const;
protected:
std::uint8_t port;
std::unique_ptr<Filter> filter;
};
} // namespace okapi

View File

@ -0,0 +1,69 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerOutput.hpp"
#include "okapi/api/util/logging.hpp"
namespace okapi {
class ADIMotor : public ControllerOutput<double> {
public:
/**
* A motor in an ADI port.
*
* ```cpp
* auto mtr = ADIMotor('A');
* auto reversedMtr = ADIMotor('A', true);
* ```
*
* @param iport The ADI port number (``[1, 8]``, ``[a, h]``, ``[A, H]``).
* @param ireverse Whether the motor is reversed.
* @param logger The logger that initialization warnings will be logged to.
*/
ADIMotor(std::uint8_t iport,
bool ireverse = false,
const std::shared_ptr<Logger> &logger = Logger::getDefaultLogger());
/**
* A motor in an ADI port.
*
* ```cpp
* auto mtr = ADIMotor({1, 'A'}, false);
* auto reversedMtr = ADIMotor({1, 'A'}, true);
* ```
*
* @param iports The ports the motor is plugged in to in the order ``{smart port, motor port}``.
* The smart port is the smart port number (``[1, 21]``). The motor port is the ADI port number
* (``[1, 8]``, ``[a, h]``, ``[A, H]``).
* @param ireverse Whether the motor is reversed.
* @param logger The logger that initialization warnings will be logged to.
*/
ADIMotor(std::pair<std::uint8_t, std::uint8_t> iports,
bool ireverse = false,
const std::shared_ptr<Logger> &logger = Logger::getDefaultLogger());
/**
* Set the voltage to the motor.
*
* @param ivoltage voltage in the range [-127, 127].
*/
virtual void moveVoltage(std::int8_t ivoltage) const;
/**
* Writes the value of the controller output. This method might be automatically called in another
* thread by the controller. The range of input values is expected to be [-1, 1].
*
* @param ivalue the controller's output in the range [-1, 1]
*/
void controllerSet(double ivalue) override;
protected:
std::uint8_t smartPort;
std::uint8_t port;
std::int8_t reversed;
};
} // namespace okapi

View File

@ -0,0 +1,457 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/motor/abstractMotor.hpp"
#include "okapi/api/util/logging.hpp"
namespace okapi {
class Motor : public AbstractMotor {
public:
/**
* A V5 motor.
*
* @param iport The port number in the range ``[1, 21]``. A negative port number is shorthand for
* reversing the motor.
*/
Motor(std::int8_t iport);
/**
* A V5 motor.
*
* @param iport The port number in the range [1, 21].
* @param ireverse Whether the motor is reversed (this setting is not written to the motor, it is
* maintained by okapi::Motor instead).
* @param igearset The internal gearset to set in the motor.
* @param iencoderUnits The encoder units to set in the motor.
* @param logger The logger that initialization warnings will be logged to.
*/
Motor(std::uint8_t iport,
bool ireverse,
AbstractMotor::gearset igearset,
AbstractMotor::encoderUnits iencoderUnits,
const std::shared_ptr<Logger> &logger = Logger::getDefaultLogger());
/******************************************************************************/
/** Motor movement functions **/
/** **/
/** These functions allow programmers to make motors move **/
/******************************************************************************/
/**
* Sets the target absolute position for the motor to move to.
*
* This movement is relative to the position of the motor when initialized or
* the position when it was most recently reset with setZeroPosition().
*
* @note This function simply sets the target for the motor, it does not block program execution
* until the movement finishes.
*
* @param iposition The absolute position to move to in the motor's encoder units
* @param ivelocity The maximum allowable velocity for the movement in RPM
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t moveAbsolute(double iposition, std::int32_t ivelocity) override;
/**
* Sets the relative target position for the motor to move to.
*
* This movement is relative to the current position of the motor. Providing 10.0 as the position
* parameter would result in the motor moving clockwise 10 units, no matter what the current
* position is.
*
* @note This function simply sets the target for the motor, it does not block program execution
* until the movement finishes.
*
* @param iposition The relative position to move to in the motor's encoder units
* @param ivelocity The maximum allowable velocity for the movement in RPM
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t moveRelative(double iposition, std::int32_t ivelocity) override;
/**
* Sets the velocity for the motor.
*
* This velocity corresponds to different actual speeds depending on the gearset
* used for the motor. This results in a range of +-100 for pros::c::red,
* +-200 for green, and +-600 for blue. The velocity
* is held with PID to ensure consistent speed, as opposed to setting the motor's
* voltage.
*
* @param ivelocity The new motor velocity from -+-100, +-200, or +-600 depending on the motor's
* gearset
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t moveVelocity(std::int16_t ivelocity) override;
/**
* Sets the voltage for the motor from -12000 to 12000.
*
* @param ivoltage The new voltage value from -12000 to 12000.
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t moveVoltage(std::int16_t ivoltage) override;
/**
* Changes the output velocity for a profiled movement (moveAbsolute or moveRelative). This will
* have no effect if the motor is not following a profiled movement.
*
* @param ivelocity The new motor velocity from -+-100, +-200, or +-600 depending on the motor's
* gearset
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t modifyProfiledVelocity(std::int32_t ivelocity) override;
/******************************************************************************/
/** Motor telemetry functions **/
/** **/
/** These functions allow programmers to collect telemetry from motors **/
/******************************************************************************/
/**
* Gets the target position set for the motor by the user.
*
* @return The target position in its encoder units or PROS_ERR_F if the operation failed,
* setting errno.
*/
double getTargetPosition() override;
/**
* Gets the absolute position of the motor in its encoder units.
*
* @return The motor's absolute position in its encoder units or PROS_ERR_F if the operation
* failed, setting errno.
*/
double getPosition() override;
/**
* Sets the "absolute" zero position of the motor to its current position.
*
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t tarePosition() override;
/**
* Gets the velocity commanded to the motor by the user.
*
* @return The commanded motor velocity from +-100, +-200, or +-600, or PROS_ERR if the operation
* failed, setting errno.
*/
std::int32_t getTargetVelocity() override;
/**
* Gets the actual velocity of the motor.
*
* @return The motor's actual velocity in RPM or PROS_ERR_F if the operation failed, setting
* errno.
*/
double getActualVelocity() override;
/**
* Gets the current drawn by the motor in mA.
*
* @return The motor's current in mA or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t getCurrentDraw() override;
/**
* Gets the direction of movement for the motor.
*
* @return 1 for moving in the positive direction, -1 for moving in the negative direction, and
* PROS_ERR if the operation failed, setting errno.
*/
std::int32_t getDirection() override;
/**
* Gets the efficiency of the motor in percent.
*
* An efficiency of 100% means that the motor is moving electrically while
* drawing no electrical power, and an efficiency of 0% means that the motor
* is drawing power but not moving.
*
* @return The motor's efficiency in percent or PROS_ERR_F if the operation failed, setting errno.
*/
double getEfficiency() override;
/**
* Checks if the motor is drawing over its current limit.
*
* @return 1 if the motor's current limit is being exceeded and 0 if the current limit is not
* exceeded, or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t isOverCurrent() override;
/**
* Checks if the motor's temperature is above its limit.
*
* @return 1 if the temperature limit is exceeded and 0 if the the temperature is below the limit,
* or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t isOverTemp() override;
/**
* Checks if the motor is stopped.
*
* Although this function forwards data from the motor, the motor presently does not provide any
* value. This function returns PROS_ERR with errno set to ENOSYS.
*
* @return 1 if the motor is not moving, 0 if the motor is moving, or PROS_ERR if the operation
* failed, setting errno
*/
std::int32_t isStopped() override;
/**
* Checks if the motor is at its zero position.
*
* Although this function forwards data from the motor, the motor presently does not provide any
* value. This function returns PROS_ERR with errno set to ENOSYS.
*
* @return 1 if the motor is at zero absolute position, 0 if the motor has moved from its absolute
* zero, or PROS_ERR if the operation failed, setting errno
*/
std::int32_t getZeroPositionFlag() override;
/**
* Gets the faults experienced by the motor. Compare this bitfield to the bitmasks in
* pros::motor_fault_e_t.
*
* @return A currently unknown bitfield containing the motor's faults. 0b00000100 = Current Limit
* Hit
*/
uint32_t getFaults() override;
/**
* Gets the flags set by the motor's operation. Compare this bitfield to the bitmasks in
* pros::motor_flag_e_t.
*
* @return A currently unknown bitfield containing the motor's flags. These seem to be unrelated
* to the individual get_specific_flag functions
*/
uint32_t getFlags() override;
/**
* Gets the raw encoder count of the motor at a given timestamp.
*
* @param timestamp A pointer to a time in milliseconds for which the encoder count will be
* returned. If NULL, the timestamp at which the encoder count was read will not be supplied
*
* @return The raw encoder count at the given timestamp or PROS_ERR if the operation failed.
*/
std::int32_t getRawPosition(std::uint32_t *timestamp) override;
/**
* Gets the power drawn by the motor in Watts.
*
* @return The motor's power draw in Watts or PROS_ERR_F if the operation failed, setting errno.
*/
double getPower() override;
/**
* Gets the temperature of the motor in degrees Celsius.
*
* @return The motor's temperature in degrees Celsius or PROS_ERR_F if the operation failed,
* setting errno.
*/
double getTemperature() override;
/**
* Gets the torque generated by the motor in Newton Metres (Nm).
*
* @return The motor's torque in NM or PROS_ERR_F if the operation failed, setting errno.
*/
double getTorque() override;
/**
* Gets the voltage delivered to the motor in millivolts.
*
* @return The motor's voltage in V or PROS_ERR_F if the operation failed, setting errno.
*/
std::int32_t getVoltage() override;
/******************************************************************************/
/** Motor configuration functions **/
/** **/
/** These functions allow programmers to configure the behavior of motors **/
/******************************************************************************/
/**
* Sets one of AbstractMotor::brakeMode to the motor.
*
* @param imode The new motor brake mode to set for the motor
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setBrakeMode(AbstractMotor::brakeMode imode) override;
/**
* Gets the brake mode that was set for the motor.
*
* @return One of brakeMode, according to what was set for the motor, or brakeMode::invalid if the
* operation failed, setting errno.
*/
brakeMode getBrakeMode() override;
/**
* Sets the current limit for the motor in mA.
*
* @param ilimit The new current limit in mA
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setCurrentLimit(std::int32_t ilimit) override;
/**
* Gets the current limit for the motor in mA. The default value is 2500 mA.
*
* @return The motor's current limit in mA or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t getCurrentLimit() override;
/**
* Sets one of AbstractMotor::encoderUnits for the motor encoder.
*
* @param iunits The new motor encoder units
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setEncoderUnits(AbstractMotor::encoderUnits iunits) override;
/**
* Gets the encoder units that were set for the motor.
*
* @return One of encoderUnits according to what is set for the motor or encoderUnits::invalid if
* the operation failed.
*/
encoderUnits getEncoderUnits() override;
/**
* Sets one of AbstractMotor::gearset for the motor.
*
* @param igearset The new motor gearset
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setGearing(AbstractMotor::gearset igearset) override;
/**
* Gets the gearset that was set for the motor.
*
* @return One of gearset according to what is set for the motor, or gearset::invalid if the
* operation failed.
*/
gearset getGearing() override;
/**
* Sets the reverse flag for the motor. This will invert its movements and the values returned for
* its position.
*
* @param ireverse True reverses the motor, false is default
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setReversed(bool ireverse) override;
/**
* Sets the voltage limit for the motor in Volts.
*
* @param ilimit The new voltage limit in Volts
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
std::int32_t setVoltageLimit(std::int32_t ilimit) override;
/**
* Sets new PID constants.
*
* @param ikF the feed-forward constant
* @param ikP the proportional constant
* @param ikI the integral constant
* @param ikD the derivative constant
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t setPosPID(double ikF, double ikP, double ikI, double ikD);
/**
* Sets new PID constants.
*
* @param ikF the feed-forward constant
* @param ikP the proportional constant
* @param ikI the integral constant
* @param ikD the derivative constant
* @param ifilter a constant used for filtering the profile acceleration
* @param ilimit the integral limit
* @param ithreshold the threshold for determining if a position movement has reached its goal
* @param iloopSpeed the rate at which the PID computation is run (in ms)
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t setPosPIDFull(double ikF,
double ikP,
double ikI,
double ikD,
double ifilter,
double ilimit,
double ithreshold,
double iloopSpeed);
/**
* Sets new PID constants.
*
* @param ikF the feed-forward constant
* @param ikP the proportional constant
* @param ikI the integral constant
* @param ikD the derivative constant
* @return `1` if the operation was successful or `PROS_ERR` if the operation failed, setting
* errno.
*/
virtual std::int32_t setVelPID(double ikF, double ikP, double ikI, double ikD);
/**
* Sets new PID constants.
*
* @param ikF the feed-forward constant
* @param ikP the proportional constant
* @param ikI the integral constant
* @param ikD the derivative constant
* @param ifilter a constant used for filtering the profile acceleration
* @param ilimit the integral limit
* @param ithreshold the threshold for determining if a position movement has reached its goal
* @param iloopSpeed the rate at which the PID computation is run (in ms)
* @return 1 if the operation was successful or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t setVelPIDFull(double ikF,
double ikP,
double ikI,
double ikD,
double ifilter,
double ilimit,
double ithreshold,
double iloopSpeed);
/**
* Get the encoder associated with this motor.
*
* @return The encoder for this motor.
*/
std::shared_ptr<ContinuousRotarySensor> getEncoder() override;
/**
* Writes the value of the controller output. This method might be automatically called in another
* thread by the controller. The range of input values is expected to be `[-1, 1]`.
*
* @param ivalue The controller's output in the range `[-1, 1]`.
*/
void controllerSet(double ivalue) override;
/**
* @return The port number.
*/
std::uint8_t getPort() const;
/**
* @return Whether this motor is reversed.
*/
bool isReversed() const;
protected:
std::uint8_t port;
std::int8_t reversed{1};
};
} // namespace okapi

View File

@ -0,0 +1,400 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/device/motor/abstractMotor.hpp"
#include "okapi/api/util/logging.hpp"
#include "okapi/impl/device/motor/motor.hpp"
#include <initializer_list>
#include <vector>
namespace okapi {
class MotorGroup : public AbstractMotor {
public:
/**
* A group of V5 motors which act as one motor (i.e. they are mechanically linked). A MotorGroup
* requires at least one motor. If no motors are supplied, a `std::invalid_argument` exception is
* thrown.
*
* @param imotors The motors in this group.
* @param ilogger The logger this instance will log initialization warnings to.
*/
MotorGroup(const std::initializer_list<Motor> &imotors,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* A group of V5 motors which act as one motor (i.e. they are mechanically linked). A MotorGroup
* requires at least one motor. If no motors are supplied, a `std::invalid_argument` exception is
* thrown.
*
* @param imotors The motors in this group.
* @param ilogger The logger this instance will log initialization warnings to.
*/
MotorGroup(const std::initializer_list<std::shared_ptr<AbstractMotor>> &imotors,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/******************************************************************************/
/** Motor movement functions **/
/** **/
/** These functions allow programmers to make motors move **/
/******************************************************************************/
/**
* Sets the target absolute position for the motor to move to.
*
* This movement is relative to the position of the motor when initialized or
* the position when it was most recently reset with setZeroPosition().
*
* @note This function simply sets the target for the motor, it does not block program execution
* until the movement finishes.
*
* @param iposition The absolute position to move to in the motor's encoder units
* @param ivelocity The maximum allowable velocity for the movement in RPM
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t moveAbsolute(double iposition, std::int32_t ivelocity) override;
/**
* Sets the relative target position for the motor to move to.
*
* This movement is relative to the current position of the motor. Providing 10.0 as the position
* parameter would result in the motor moving clockwise 10 units, no matter what the current
* position is.
*
* @note This function simply sets the target for the motor, it does not block program execution
* until the movement finishes.
*
* @param iposition The relative position to move to in the motor's encoder units
* @param ivelocity The maximum allowable velocity for the movement in RPM
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t moveRelative(double iposition, std::int32_t ivelocity) override;
/**
* Sets the velocity for the motor.
*
* This velocity corresponds to different actual speeds depending on the gearset
* used for the motor. This results in a range of +-100 for pros::c::red,
* +-200 for green, and +-600 for blue. The velocity
* is held with PID to ensure consistent speed, as opposed to setting the motor's
* voltage.
*
* @param ivelocity The new motor velocity from -+-100, +-200, or +-600 depending on the motor's
* gearset
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t moveVelocity(std::int16_t ivelocity) override;
/**
* Sets the voltage for the motor from `-12000` to `12000`.
*
* @param ivoltage The new voltage value from `-12000` to `12000`.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t moveVoltage(std::int16_t ivoltage) override;
/**
* Changes the output velocity for a profiled movement (moveAbsolute or moveRelative). This will
* have no effect if the motor is not following a profiled movement.
*
* @param ivelocity The new motor velocity from `+-100`, `+-200`, or `+-600` depending on the
* motor's gearset.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t modifyProfiledVelocity(std::int32_t ivelocity) override;
/******************************************************************************/
/** Motor telemetry functions **/
/** **/
/** These functions allow programmers to collect telemetry from motors **/
/******************************************************************************/
/**
* Gets the target position set for the motor by the user.
*
* @return The target position in its encoder units or `PROS_ERR_F` if the operation failed,
* setting errno.
*/
double getTargetPosition() override;
/**
* Gets the absolute position of the motor in its encoder units.
*
* @return The motor's absolute position in its encoder units or `PROS_ERR_F` if the operation
* failed, setting errno.
*/
double getPosition() override;
/**
* Sets the "absolute" zero position of the motor to its current position.
*
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t tarePosition() override;
/**
* Gets the velocity commanded to the motor by the user.
*
* @return The commanded motor velocity from +-100, +-200, or +-600, or `PROS_ERR` if the
* operation failed, setting errno.
*/
std::int32_t getTargetVelocity() override;
/**
* Gets the actual velocity of the motor.
*
* @return The motor's actual velocity in RPM or `PROS_ERR_F` if the operation failed, setting
* errno.
*/
double getActualVelocity() override;
/**
* Gets the current drawn by the motor in mA.
*
* @return The motor's current in mA or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t getCurrentDraw() override;
/**
* Gets the direction of movement for the motor.
*
* @return 1 for moving in the positive direction, -1 for moving in the negative direction, and
* `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t getDirection() override;
/**
* Gets the efficiency of the motor in percent.
*
* An efficiency of 100% means that the motor is moving electrically while
* drawing no electrical power, and an efficiency of 0% means that the motor
* is drawing power but not moving.
*
* @return The motor's efficiency in percent or `PROS_ERR_F` if the operation failed, setting
* errno.
*/
double getEfficiency() override;
/**
* Checks if the motor is drawing over its current limit.
*
* @return 1 if the motor's current limit is being exceeded and 0 if the current limit is not
* exceeded, or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t isOverCurrent() override;
/**
* Checks if the motor's temperature is above its limit.
*
* @return 1 if the temperature limit is exceeded and 0 if the the temperature is below the limit,
* or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t isOverTemp() override;
/**
* Checks if the motor is stopped.
*
* Although this function forwards data from the motor, the motor presently does not provide any
* value. This function returns `PROS_ERR` with errno set to `ENOSYS`.
*
* @return 1 if the motor is not moving, 0 if the motor is moving, or `PROS_ERR` if the operation
* failed, setting errno
*/
std::int32_t isStopped() override;
/**
* Checks if the motor is at its zero position.
*
* Although this function forwards data from the motor, the motor presently does not provide any
* value. This function returns `PROS_ERR` with errno set to `ENOSYS`.
*
* @return 1 if the motor is at zero absolute position, `0` if the motor has moved from its
* absolute zero, or `PROS_ERR` if the operation failed, setting errno
*/
std::int32_t getZeroPositionFlag() override;
/**
* Gets the faults experienced by the motor. Compare this bitfield to the bitmasks in
* pros::motor_fault_e_t.
*
* @return A currently unknown bitfield containing the motor's faults. `0b00000100` = Current
* Limit Hit
*/
uint32_t getFaults() override;
/**
* Gets the flags set by the motor's operation. Compare this bitfield to the bitmasks in
* pros::motor_flag_e_t.
*
* @return A currently unknown bitfield containing the motor's flags. These seem to be unrelated
* to the individual get_specific_flag functions
*/
uint32_t getFlags() override;
/**
* Gets the raw encoder count of the motor at a given timestamp.
*
* @param timestamp A pointer to a time in milliseconds for which the encoder count will be
* returned. If `NULL`, the timestamp at which the encoder count was read will not be supplied.
* @return The raw encoder count at the given timestamp or `PROS_ERR` if the operation failed.
*/
std::int32_t getRawPosition(std::uint32_t *timestamp) override;
/**
* Gets the power drawn by the motor in Watts.
*
* @return The motor's power draw in Watts or `PROS_ERR_F` if the operation failed, setting errno.
*/
double getPower() override;
/**
* Gets the temperature of the motor in degrees Celsius.
*
* @return The motor's temperature in degrees Celsius or `PROS_ERR_F` if the operation failed,
* setting errno.
*/
double getTemperature() override;
/**
* Gets the torque generated by the motor in Newton Metres (Nm).
*
* @return The motor's torque in NM or `PROS_ERR_F` if the operation failed, setting errno.
*/
double getTorque() override;
/**
* Gets the voltage delivered to the motor in millivolts.
*
* @return The motor's voltage in V or `PROS_ERR_F` if the operation failed, setting errno.
*/
std::int32_t getVoltage() override;
/******************************************************************************/
/** Motor configuration functions **/
/** **/
/** These functions allow programmers to configure the behavior of motors **/
/******************************************************************************/
/**
* Sets one of AbstractMotor::brakeMode to the motor.
*
* This function uses the following values of errno when an error state is reached:
* EACCES - Another resource is currently trying to access the port.
*
* @param imode The new motor brake mode to set for the motor.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setBrakeMode(AbstractMotor::brakeMode imode) override;
/**
* Gets the brake mode that was set for the motor.
*
* @return One of brakeMode, according to what was set for the motor, or brakeMode::invalid if the
* operation failed, setting errno.
*/
brakeMode getBrakeMode() override;
/**
* Sets the current limit for the motor in mA.
*
* This function uses the following values of errno when an error state is reached:
* EACCES - Another resource is currently trying to access the port.
*
* @param ilimit The new current limit in mA.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setCurrentLimit(std::int32_t ilimit) override;
/**
* Gets the current limit for the motor in mA. The default value is `2500` mA.
*
* @return The motor's current limit in mA or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t getCurrentLimit() override;
/**
* Sets one of AbstractMotor::encoderUnits for the motor encoder.
*
* @param iunits The new motor encoder units.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setEncoderUnits(AbstractMotor::encoderUnits iunits) override;
/**
* Gets the encoder units that were set for the motor.
*
* @return One of encoderUnits according to what is set for the motor or encoderUnits::invalid if
* the operation failed.
*/
encoderUnits getEncoderUnits() override;
/**
* Sets one of AbstractMotor::gearset for the motor.
*
* @param igearset The new motor gearset.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setGearing(AbstractMotor::gearset igearset) override;
/**
* Gets the gearset that was set for the motor.
*
* @return One of gearset according to what is set for the motor, or `gearset::invalid` if the
* operation failed.
*/
gearset getGearing() override;
/**
* Sets the reverse flag for the motor. This will invert its movements and the values returned for
* its position.
*
* @param ireverse True reverses the motor, false is default.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setReversed(bool ireverse) override;
/**
* Sets the voltage limit for the motor in Volts.
*
* @param ilimit The new voltage limit in Volts.
* @return 1 if the operation was successful or `PROS_ERR` if the operation failed, setting errno.
*/
std::int32_t setVoltageLimit(std::int32_t ilimit) override;
/**
* Writes the value of the controller output. This method might be automatically called in another
* thread by the controller. The range of input values is expected to be `[-1, 1]`.
*
* @param ivalue the controller's output in the range `[-1, 1]`
*/
void controllerSet(double ivalue) override;
/**
* Gets the number of motors in the motor group.
*
* @return size_t
*/
size_t getSize();
/**
* Get the encoder associated with the first motor in this group.
*
* @return The encoder for the motor at index `0`.
*/
std::shared_ptr<ContinuousRotarySensor> getEncoder() override;
/**
* Get the encoder associated with this motor.
*
* @param index The index in `motors` to get the encoder from.
* @return The encoder for the motor at `index`.
*/
virtual std::shared_ptr<ContinuousRotarySensor> getEncoder(std::size_t index);
protected:
std::vector<std::shared_ptr<AbstractMotor>> motors;
};
} // namespace okapi

View File

@ -0,0 +1,140 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerInput.hpp"
#include "okapi/api/filter/passthroughFilter.hpp"
#include <memory>
namespace okapi {
enum class OpticalSensorOutput {
hue, ///< The color.
saturation, ///< The color's intensity relative to its brightness.
brightness ///< The amount of light.
};
class OpticalSensor : public ControllerInput<double> {
public:
/**
* An optical sensor on a V5 port.
*
* ```cpp
* auto osHue = OpticalSensor(1);
* auto osSat = OpticalSensor(1, OpticalSensorOutput::saturation);
* ```
*
* @param iport The V5 port the device uses.
* @param ioutput Which sensor output to return from (@ref okapi::OpticalSensor::get).
* @param idisableGestures Whether to automatically disable the gesture sensor. Typically, the
* gesture sensor should be disabled unless you are going to use gestures because the optical
* sensor does not update color information while detecting a gesture.
* @param ifilter The filter to use to filter the sensor output. Only the selected output (via
* ``ioutput``) is filtered; the other outputs are untouched.
*/
OpticalSensor(std::uint8_t iport,
OpticalSensorOutput ioutput = OpticalSensorOutput::hue,
bool idisableGestures = true,
std::unique_ptr<Filter> ifilter = std::make_unique<PassthroughFilter>());
virtual ~OpticalSensor() = default;
/**
* Get the current filtered value of the selected output (configured by the constructor).
*
* @return The current filtered value of the selected output (configured by the constructor).
*/
double get();
/**
* Get the current hue value in the range ``[0, 360)``.
*
* @return The current hue value in the range ``[0, 360)``.
*/
double getHue() const;
/**
* Get the current brightness value in the range ``[0, 1]``.
*
* @return The current brightness value in the range ``[0, 1]``.
*/
double getBrightness() const;
/**
* Get the current saturation value in the range ``[0, 1]``.
*
* @return The current saturation value in the range ``[0, 1]``.
*/
double getSaturation() const;
/**
* Get the PWM value of the white LED in the range ``[0, 100]``.
*
* @return The PWM value of the white LED in the range ``[0, 100]`` or ``PROS_ERR`` if the
* operation failed, setting ``errno``.
*/
int32_t getLedPWM() const;
/**
* Set the PWM value of the white LED in the range ``[0, 100]``.
*
* @param value The PWM value in the range ``[0, 100]``.
* @return ``1`` if the operation was successful or ``PROS_ERR`` if the operation failed, setting
* ``errno``.
*/
int32_t setLedPWM(std::uint8_t ivalue) const;
/**
* Get the current proximity value in the range ``[0, 255]``. This is not available if gestures
* are being detected.
*
* @return The current proximity value in the range ``[0, 255]``.
*/
int32_t getProximity() const;
/**
* Get the processed RGBC data from the sensor.
*
* @return The RGBC value if the operation was successful. If the operation failed, all field are
* set to ``PROS_ERR`` and ``errno`` is set.
*/
pros::c::optical_rgb_s_t getRGB() const;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return The same as [get](@ref okapi::OpticalSensor::get).
*/
double controllerGet() override;
/**
* Enable gestures.
*
* @return ``1`` if the operation was successful or ``PROS_ERR`` if the operation failed, setting
* ``errno``.
*/
int32_t enableGestures() const;
/**
* Disable gestures.
*
* @return ``1`` if the operation was successful or ``PROS_ERR`` if the operation failed, setting
* ``errno``.
*/
int32_t disableGestures() const;
protected:
std::uint8_t port;
OpticalSensorOutput output;
std::unique_ptr<Filter> filter;
/**
* Gets the output directly from the sensor using the selected output.
*/
double getSelectedOutput();
};
} // namespace okapi

View File

@ -0,0 +1,109 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerInput.hpp"
#include "okapi/api/device/rotarysensor/continuousRotarySensor.hpp"
namespace okapi {
enum class IMUAxes {
z, ///< Yaw Axis
y, ///< Pitch Axis
x ///< Roll Axis
};
class IMU : public ContinuousRotarySensor {
public:
/**
* An inertial sensor on the given port. The IMU returns an angle about the selected axis in
* degrees.
*
* ```cpp
* auto imuZ = IMU(1);
* auto imuX = IMU(1, IMUAxes::x);
* ```
*
* @param iport The port number in the range ``[1, 21]``.
* @param iaxis The axis of the inertial sensor to measure, default `IMUAxes::z`.
*/
IMU(std::uint8_t iport, IMUAxes iaxis = IMUAxes::z);
/**
* Get the current rotation about the configured axis.
*
* @return The current sensor value or ``PROS_ERR``.
*/
double get() const override;
/**
* Get the current sensor value remapped into the target range (``[-1800, 1800]`` by default).
*
* @param iupperBound The upper bound of the range.
* @param ilowerBound The lower bound of the range.
* @return The remapped sensor value.
*/
double getRemapped(double iupperBound = 1800, double ilowerBound = -1800) const;
/**
* Get the current acceleration along the configured axis.
*
* @return The current sensor value or ``PROS_ERR``.
*/
double getAcceleration() const;
/**
* Reset the rotation value to zero.
*
* @return ``1`` or ``PROS_ERR``.
*/
std::int32_t reset() override;
/**
* Resets rotation value to desired value
* For example, ``reset(0)`` will reset the sensor to zero.
* But ``reset(90)`` will reset the sensor to 90 degrees.
*
* @param inewAngle desired reset value
* @return ``1`` or ``PROS_ERR``.
*/
std::int32_t reset(double inewAngle);
/**
* Calibrate the IMU. Resets the rotation value to zero. Calibration is expected to take two
* seconds, but is bounded to five seconds.
*
* @return ``1`` or ``PROS_ERR``.
*/
std::int32_t calibrate();
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return The current sensor value or ``PROS_ERR``.
*/
double controllerGet() override;
/**
* @return Whether the IMU is calibrating.
*/
bool isCalibrating() const;
protected:
std::uint8_t port;
IMUAxes axis;
double offset = 0;
/**
* Get the current rotation about the configured axis. The internal offset is not accounted for
* or modified. This just reads from the sensor.
*
* @return The current sensor value or ``PROS_ERR``.
*/
double readAngle() const;
};
} // namespace okapi

View File

@ -0,0 +1,73 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/rotarysensor/continuousRotarySensor.hpp"
namespace okapi {
class ADIEncoder : public ContinuousRotarySensor {
public:
/**
* An encoder in an ADI port.
*
* ```cpp
* auto enc = ADIEncoder('A', 'B', false);
* auto reversedEnc = ADIEncoder('A', 'B', true);
* ```
*
* @param iportTop The "top" wire from the encoder with the removable cover side up. This must be
* in port ``1``, ``3``, ``5``, or ``7`` (``A``, ``C``, ``E``, or ``G``).
* @param iportBottom The "bottom" wire from the encoder. This must be in port ``2``, ``4``,
* ``6``, or ``8`` (``B``, ``D``, ``F``, or ``H``).
* @param ireversed Whether the encoder is reversed.
*/
ADIEncoder(std::uint8_t iportTop, std::uint8_t iportBottom, bool ireversed = false);
/**
* An encoder in an ADI port.
*
* ```cpp
* auto enc = ADIEncoder({1, 'A', 'B'}, false);
* auto reversedEnc = ADIEncoder({1, 'A', 'B'}, true);
* ```
*
* @param iports The ports the encoder is plugged in to in the order ``{smart port, top port,
* bottom port}``. The smart port is the smart port number (``[1, 21]``). The top port is the
* "top" wire from the encoder with the removable cover side up. This must be in port ``1``,
* ``3``, ``5``, or
* ``7`` (``A``, ``C``, ``E``, or ``G``). The bottom port is the "bottom" wire from the encoder.
* This must be in port ``2``, ``4``, ``6``, or ``8`` (``B``, ``D``, ``F``, or ``H``).
* @param ireversed Whether the encoder is reversed.
*/
ADIEncoder(std::tuple<std::uint8_t, std::uint8_t, std::uint8_t> iports, bool ireversed = false);
/**
* Get the current sensor value.
*
* @return the current sensor value, or `PROS_ERR` on a failure.
*/
virtual double get() const override;
/**
* Reset the sensor to zero.
*
* @return `1` on success, `PROS_ERR` on fail
*/
virtual std::int32_t reset() override;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return the current sensor value, or `PROS_ERR` on a failure.
*/
virtual double controllerGet() override;
protected:
pros::c::ext_adi_encoder_t enc;
};
} // namespace okapi

View File

@ -0,0 +1,82 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/control/controllerInput.hpp"
#include "okapi/api/device/rotarysensor/continuousRotarySensor.hpp"
namespace okapi {
class ADIGyro : public ContinuousRotarySensor {
public:
/**
* A gyroscope on the given ADI port. If the port has not previously been configured as a gyro,
* then the constructor will block for 1 second for calibration. The gyro measures in tenths of a
* degree, so there are ``3600`` measurement points per revolution.
*
* ```cpp
* auto gyro = ADIGyro('A');
* ```
*
* @param iport The ADI port number (``[1, 8]``, ``[a, h]``, ``[A, H]``).
* @param imultiplier A value multiplied by the gyro heading value.
*/
ADIGyro(std::uint8_t iport, double imultiplier = 1);
/**
* A gyroscope on the given ADI port. If the port has not previously been configured as a gyro,
* then the constructor will block for 1 second for calibration. The gyro measures in tenths of a
* degree, so there are 3600 measurement points per revolution.
*
* ```cpp
* auto gyro = ADIGyro({1, 'A'}, 1);
* ```
*
* Note to developers: Keep the default value on imultiplier so that users get an error if they do
* ADIGyro({1, 'A'}). Without it, this calls the non-ext-adi constructor.
*
* @param iports The ports the gyro is plugged in to in the order ``{smart port, gyro port}``. The
* smart port is the smart port number (``[1, 21]``). The gyro port is the ADI port number (``[1,
* 8]``, ``[a, h]``, ``[A, H]``).
* @param imultiplier A value multiplied by the gyro heading value.
*/
ADIGyro(std::pair<std::uint8_t, std::uint8_t> iports, double imultiplier = 1);
/**
* Get the current sensor value.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
double get() const override;
/**
* Get the current sensor value remapped into the target range (``[-1800, 1800]`` by default).
*
* @param iupperBound the upper bound of the range.
* @param ilowerBound the lower bound of the range.
* @return the remapped sensor value.
*/
double getRemapped(double iupperBound = 1800, double ilowerBound = -1800) const;
/**
* Reset the sensor to zero.
*
* @return `1` on success, `PROS_ERR` on fail
*/
std::int32_t reset() override;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
double controllerGet() override;
protected:
pros::c::ext_adi_gyro_t gyro;
};
} // namespace okapi

View File

@ -0,0 +1,56 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/rotarysensor/continuousRotarySensor.hpp"
#include "okapi/impl/device/motor/motor.hpp"
namespace okapi {
class IntegratedEncoder : public ContinuousRotarySensor {
public:
/**
* Integrated motor encoder. Uses the encoder inside the V5 motor.
*
* @param imotor The motor to use the encoder from.
*/
IntegratedEncoder(const okapi::Motor &imotor);
/**
* Integrated motor encoder. Uses the encoder inside the V5 motor.
*
* @param iport The motor's port number in the range [1, 21].
* @param ireversed Whether the encoder is reversed.
*/
IntegratedEncoder(std::int8_t iport, bool ireversed = false);
/**
* Get the current sensor value.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
virtual double get() const override;
/**
* Reset the sensor to zero.
*
* @return `1` on success, `PROS_ERR` on fail
*/
virtual std::int32_t reset() override;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
virtual double controllerGet() override;
protected:
std::uint8_t port;
std::int8_t reversed{1};
};
} // namespace okapi

View File

@ -0,0 +1,57 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/rotarysensor/rotarySensor.hpp"
namespace okapi {
class Potentiometer : public RotarySensor {
public:
/**
* A potentiometer in an ADI port.
*
* ```cpp
* auto pot = Potentiometer('A');
* ```
*
* @param iport The ADI port number (``[1, 8]``, ``[a, h]``, ``[A, H]``).
*/
Potentiometer(std::uint8_t iport);
/**
* A potentiometer in an ADI port.
*
* ```cpp
* auto pot = Potentiometer({1, 'A'});
* ```
*
* @param iports The ports the potentiometer is plugged in to in the order ``{smart port,
* potentiometer port}``. The smart port is the smart port number (``[1, 21]``). The potentiometer
* port is the ADI port number (``[1, 8]``, ``[a, h]``, ``[A, H]``).
*/
Potentiometer(std::pair<std::uint8_t, std::uint8_t> iports);
/**
* Get the current sensor value.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
virtual double get() const override;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return the current sensor value, or ``PROS_ERR`` on a failure.
*/
virtual double controllerGet() override;
protected:
std::uint8_t smartPort;
std::uint8_t port;
};
} // namespace okapi

View File

@ -0,0 +1,64 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "okapi/api/device/rotarysensor/continuousRotarySensor.hpp"
namespace okapi {
class RotationSensor : public ContinuousRotarySensor {
public:
/**
* A rotation sensor in a V5 port.
*
* ```cpp
* auto r = RotationSensor(1);
* auto reversedR = RotationSensor(1, true);
* ```
*
* @param iport The V5 port the device uses.
* @param ireversed Whether the sensor is reversed. This will set the reversed state in the
* kernel.
*/
RotationSensor(std::uint8_t iport, bool ireversed = false);
/**
* Get the current rotation in degrees.
*
* @return The current rotation in degrees or ``PROS_ERR_F`` if the operation failed, setting
* ``errno``.
*/
double get() const override;
/**
* Reset the sensor to zero.
*
* @return ``1`` if the operation was successful or ``PROS_ERR`` if the operation failed, setting
* ``errno``.
*/
std::int32_t reset() override;
/**
* Get the sensor value for use in a control loop. This method might be automatically called in
* another thread by the controller.
*
* @return The same as [get](@ref okapi::RotationSensor::get).
*/
double controllerGet() override;
/**
* Get the current rotational velocity estimate in degrees per second.
*
* @return The current rotational velocity estimate in degrees per second or ``PROS_ERR_F`` if the
* operation failed, setting ``errno``.
*/
double getVelocity() const;
protected:
std::uint8_t port;
std::int8_t reversed{1};
};
} // namespace okapi

View File

@ -0,0 +1,68 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/filter/velMath.hpp"
#include <memory>
namespace okapi {
class VelMathFactory {
public:
/**
* Velocity math helper. Calculates filtered velocity. Throws a std::invalid_argument exception
* if iticksPerRev is zero. Averages the last two readings.
*
* @param iticksPerRev The number of ticks per revolution.
* @param isampleTime The minimum time between samples.
* @param ilogger The logger this instance will log to.
*/
static VelMath create(double iticksPerRev,
QTime isampleTime = 0_ms,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity math helper. Calculates filtered velocity. Throws a std::invalid_argument exception
* if iticksPerRev is zero. Averages the last two readings.
*
* @param iticksPerRev The number of ticks per revolution.
* @param isampleTime The minimum time between samples.
* @param ilogger The logger this instance will log to.
*/
static std::unique_ptr<VelMath>
createPtr(double iticksPerRev,
QTime isampleTime = 0_ms,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity math helper. Calculates filtered velocity. Throws a std::invalid_argument exception
* if iticksPerRev is zero.
*
* @param iticksPerRev The number of ticks per revolution.
* @param ifilter The filter used for filtering the calculated velocity.
* @param isampleTime The minimum time between samples.
* @param ilogger The logger this instance will log to.
*/
static VelMath create(double iticksPerRev,
std::unique_ptr<Filter> ifilter,
QTime isampleTime = 0_ms,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
/**
* Velocity math helper. Calculates filtered velocity. Throws a std::invalid_argument exception
* if iticksPerRev is zero.
*
* @param iticksPerRev The number of ticks per revolution.
* @param ifilter The filter used for filtering the calculated velocity.
* @param isampleTime The minimum time between samples.
* @param ilogger The logger this instance will log to.
*/
static std::unique_ptr<VelMath>
createPtr(double iticksPerRev,
std::unique_ptr<Filter> ifilter,
QTime isampleTime = 0_ms,
const std::shared_ptr<Logger> &ilogger = Logger::getDefaultLogger());
};
} // namespace okapi

View File

@ -0,0 +1,34 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/impl/util/timeUtilFactory.hpp"
namespace okapi {
/**
* A TimeUtilFactory that supplies the SettledUtil parameters passed in the constructor to every
* new TimeUtil instance.
*/
class ConfigurableTimeUtilFactory : public TimeUtilFactory {
public:
ConfigurableTimeUtilFactory(double iatTargetError = 50,
double iatTargetDerivative = 5,
const QTime &iatTargetTime = 250_ms);
/**
* Creates a TimeUtil with the SettledUtil parameters specified in the constructor by
* delegating to TimeUtilFactory::withSettledUtilParams.
*
* @return A TimeUtil with the SettledUtil parameters specified in the constructor.
*/
TimeUtil create() override;
private:
double atTargetError;
double atTargetDerivative;
QTime atTargetTime;
};
} // namespace okapi

View File

@ -0,0 +1,42 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/util/abstractRate.hpp"
namespace okapi {
class Rate : public AbstractRate {
public:
Rate();
/**
* Delay the current task such that it runs at the given frequency. The first delay will run for
* 1000/(ihz). Subsequent delays will adjust according to the previous runtime of the task.
*
* @param ihz the frequency
*/
void delay(QFrequency ihz) override;
/**
* Delay the current task until itime has passed. This method can be used by periodic tasks to
* ensure a consistent execution frequency.
*
* @param itime the time period
*/
void delayUntil(QTime itime) override;
/**
* Delay the current task until ims milliseconds have passed. This method can be used by
* periodic tasks to ensure a consistent execution frequency.
*
* @param ims the time period
*/
void delayUntil(uint32_t ims) override;
protected:
std::uint32_t lastTime{0};
};
} // namespace okapi

View File

@ -0,0 +1,32 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/util/timeUtil.hpp"
namespace okapi {
class TimeUtilFactory {
public:
virtual ~TimeUtilFactory() = default;
/**
* Creates a default TimeUtil.
*/
virtual TimeUtil create();
/**
* Creates a default TimeUtil.
*/
static TimeUtil createDefault();
/**
* Creates a TimeUtil with custom SettledUtil params. See SettledUtil docs.
*/
static TimeUtil withSettledUtilParams(double iatTargetError = 50,
double iatTargetDerivative = 5,
const QTime &iatTargetTime = 250_ms);
};
} // namespace okapi

View File

@ -0,0 +1,22 @@
/*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "okapi/api/util/abstractTimer.hpp"
namespace okapi {
class Timer : public AbstractTimer {
public:
Timer();
/**
* Returns the current time in units of QTime.
*
* @return the current time
*/
QTime millis() const override;
};
} // namespace okapi