Summary
| Members | Descriptions |
|---|---|
namespace xapi | |
namespace xVecLib | The main Namespace for the Library. |
struct robotAccess::coordinate | A simple struct to represent a coordinate. |
struct pidValue | Struct to hold PID values. |
struct robotAccess | The robotAccess struct allows PID and other code in xVecLib to gain access to the robot variables. |
namespace xapi
Summary
| Members | Descriptions |
|---|---|
public std::uint32_t get_pen() | |
public std::uint32_t fill_rect(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1) | |
public std::uint32_t set_pen(std::uint32_t color) | |
public std::uint32_t draw_rect(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1) | |
public std::uint32_t fill_circle(const std::int16_t x,const std::int16_t y,const std::int16_t radius) | |
public std::uint32_t draw_circle(const std::int16_t x,const std::int16_t y,const std::int16_t radius) | |
public std::uint32_t draw_line(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1) | |
public uint32_t millis(void) | |
public void delay(const uint32_t milliseconds) | |
class xapi::Mutex | |
class xapi::MotorGroup | |
class xapi::Motor | |
class xapi::IMU | |
class xapi::Rotation | |
class xapi::Encoder |
Members
public std::uint32_t get_pen()
public std::uint32_t fill_rect(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1)
public std::uint32_t set_pen(std::uint32_t color)
public std::uint32_t draw_rect(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1)
public std::uint32_t fill_circle(const std::int16_t x,const std::int16_t y,const std::int16_t radius)
public std::uint32_t draw_circle(const std::int16_t x,const std::int16_t y,const std::int16_t radius)
public std::uint32_t draw_line(const std::int16_t x0,const std::int16_t y0,const std::int16_t x1,const std::int16_t y1)
public uint32_t millis(void)
public void delay(const uint32_t milliseconds)
class xapi::Mutex
Summary
| Members | Descriptions |
|---|
Members
class xapi::MotorGroup
Summary
| Members | Descriptions |
|---|
Members
class xapi::Motor
Summary
| Members | Descriptions |
|---|
Members
class xapi::IMU
Summary
| Members | Descriptions |
|---|
Members
class xapi::Rotation
Summary
| Members | Descriptions |
|---|
Members
class xapi::Encoder
Summary
| Members | Descriptions |
|---|
Members
namespace xVecLib
The main Namespace for the Library.
Summary
| Members | Descriptions |
|---|---|
enum cAxis | An enum that contains the 2 possible axis, X and Y. |
public double calcInchesPerTick(double current,double size,double ratio) | Calculates the inches per one tick of the Motor. |
public double getTilePos(double pos) | Converts pos from inches to tiles. |
public double getPosTile(double tile) | Converts tile from tiles to inches. |
public double checkSign(double num) | Returns 0 if num is equal to 0, 1 if it's greater, -1 if it's less. |
public double convertRadians(double num) | Converts num from degrees to radians. |
public double convertDegrees(double num) | Converts num from radians to degrees. |
public double slew(double target,double current,double maxChange) | Slew rate limiter. |
public constexpr double radToDeg(double rad) | Convert radians to degrees. |
public constexpr double degToRad(double deg) | Convert degrees to radians. |
public double angleError(double angle1,double angle2,bool radians) | Calculate the error between 2 angles. Useful when calculating the error between 2 headings. |
public template<> constexpr T sgn(T value) | Return the sign of a number. |
public double avg(std::vector< double > values) | Return the average of a vector of numbers. |
public double ema(double current,double previous,double smooth) | Exponential moving average. |
public double getCurvature(Point first,Point other) | Get the signed curvature of a circle that intersects the first Point and the second Point. |
public template<> constexpr const T & clamp(const T & v,const T & lo,const T & hi) | |
public double average(std::vector< double > const & v) | |
public bool whatAxis(cAxis ax) | |
class xVecLib::control | The control class is used to control individual motors with powerful methods. |
class xVecLib::drawing | |
class xVecLib::Point | A point. Used in all path tracking methods. |
class xVecLib::robot | A class to allow basic control of the robot using the pid class. |
struct xVecLib::odom | A struct for odom devices This includes encoders, rotaion sensors, motor groups, and motors. |
struct xVecLib::moveToParams | struct containing the moveTo params |
struct xVecLib::pidSettings |
Members
enum cAxis
| Values | Descriptions |
|---|---|
| x | |
| y |
An enum that contains the 2 possible axis, X and Y.
public double calcInchesPerTick(double current,double size,double ratio)
Calculates the inches per one tick of the Motor.
Ticks represent what you are tracking (degrees)
Parameters
current
Returns
double
public double getTilePos(double pos)
Converts pos from inches to tiles.
Parameters
pos
Returns
pos in tiles
public double getPosTile(double tile)
Converts tile from tiles to inches.
Parameters
tile
Returns
double
public double checkSign(double num)
Returns 0 if num is equal to 0, 1 if it's greater, -1 if it's less.
Parameters
num
Returns
double
public double convertRadians(double num)
Converts num from degrees to radians.
Parameters
num
Returns
The value in radians of num
public double convertDegrees(double num)
Converts num from radians to degrees.
Parameters
num
Returns
The value in degrees of num
public double slew(double target,double current,double maxChange)
Slew rate limiter.
Parameters
-
targettarget value -
currentcurrent value -
maxChangemaximum change. No maximum if set to 0
Returns
double - the limited value
public constexpr double radToDeg(double rad)
Convert radians to degrees.
Parameters
radradians
Returns
double degrees
public constexpr double degToRad(double deg)
Convert degrees to radians.
Parameters
degdegrees
Returns
double radians
public double angleError(double angle1,double angle2,bool radians)
Calculate the error between 2 angles. Useful when calculating the error between 2 headings.
Parameters
-
angle1 -
angle2 -
radianstrue if angle is in radians, false if not. False by default
Returns
double wrapped angle
public template<>
constexpr T sgn(T value)
Return the sign of a number.
Parameters
xthe number to get the sign of
Returns
int - -1 if negative, 1 if positive
public double avg(std::vector< double > values)
Return the average of a vector of numbers.
Parameters
values
Returns
double
public double ema(double current,double previous,double smooth)
Exponential moving average.
Parameters
-
currentcurrent measurement -
previousprevious output -
smoothsmoothing factor (0-1). 1 means no smoothing, 0 means no change
Returns
double - the smoothed output
public double getCurvature(Point first,Point other)
Get the signed curvature of a circle that intersects the first Point and the second Point.
The circle will be tangent to the theta value of the first Point
The curvature is signed. Positive curvature means the circle is going clockwise, negative means counter-clockwise
Theta has to be in radians and in standard form. That means 0 is right and increases counter-clockwise
Parameters
Returns
double curvature
The circle will be tangent to the theta value of the first Point
The curvature is signed. Positive curvature means the circle is going clockwise, negative means counter-clockwise
Theta has to be in radians and in standard form. That means 0 is right and increases counter-clockwise
Parameters
Returns
double curvature
public template<>
constexpr const T & clamp(const T & v,const T & lo,const T & hi)
public double average(std::vector< double > const & v)
public bool whatAxis(cAxis ax)
class xVecLib::control
The control class is used to control individual motors with powerful methods.
This class provides methods for controlling the robot's movement, including the PID control loop and moveTo.
Parameters
-
rightMotorsThe motors on the right side of the robot. -
leftMotorsThe motors on the left side of the robot. -
imuThe Inertial Measurement Unit (IMU) that provides information about the robot's orientation. -
lateralSettingsThe PID values for controlling the robot's movement laterally. -
angularSettingThe PID values for controlling the robot's movement in a circular motion.
Summary
| Members | Descriptions |
|---|---|
public control(pros::MotorGroup * _rightMotors,pros::MotorGroup * _leftMotors,pros::Imu * _imu,pidSettings linearSetting,pidSettings angularSetting,double wheelDiameter,double gearRatio) | Constructor for the control class. |
Members
public control(pros::MotorGroup * _rightMotors,pros::MotorGroup * _leftMotors,pros::Imu * _imu,pidSettings linearSetting,pidSettings angularSetting,double wheelDiameter,double gearRatio)
Constructor for the control class.
Parameters
-
_rightMotorsThe motors on the right side of the robot -
_leftMotorsThe motors on the left side of the robot -
_imuThe Inertial Measurement Unit (IMU) that provides information about the robot's orientation -
linearSettingThe PID values for controlling the robot's movement laterally -
angularSettingThe PID values for controlling the robot's movement in a circular motion -
sensorsThe sensors that the robot uses for odometry
class xVecLib::drawing
Summary
| Members | Descriptions |
|---|---|
public inline drawing() | |
public void drawTile(double x,double y) | Draws a tile on the brain. Used in the xVecLib::drawing::drawField();. |
public void drawField(void) | Draws a field on the robot's brain. |
public void xVecLibScreen(void) | A screen that uses xVecLib to display internal data. |
Members
public inline drawing()
public void drawTile(double x,double y)
Draws a tile on the brain. Used in the xVecLib::drawing::drawField();.
Parameters
-
xThe x value of the tile. Ranges from 1-6 -
yThe y value of the tile. Ranges from 1-6
public void drawField(void)
Draws a field on the robot's brain.
This function draws a field on the robot's brain using the data from xVecLib::drawing::xfieldvalue and yfieldvalue
public void xVecLibScreen(void)
A screen that uses xVecLib to display internal data.
This function displays a screen that uses xVecLib to display internal data about the robot.
class xVecLib::Point
A point. Used in all path tracking methods.
Summary
| Members | Descriptions |
|---|---|
public double x | x value |
public double y | y value |
public double theta | theta value |
public inline Point(double X,double Y,double theta) | Create a new Point. |
public inline double getX() | |
public inline double getY() | |
public inline double getAngle() | |
public inline void setX(double Num) | |
public inline void setY(double Num) | |
public inline void setAngle(double Ang) | |
public inline double getCurve() | |
public inline double getVelocity() | |
public inline void setCurve(double curve) | |
public inline void setVelocity(double vel) | |
public inline void ExportPoint() | |
public Point operator+(const Point & other) | Add a Point to this Point. |
public Point operator-(const Point & other) | Subtract a Point from this Point. |
public double operator*(const Point & other) | Multiply a Point by this Point. |
public Point operator*(const double & other) | Multiply a Point by a double. |
public Point operator/(const double & other) | Divide a Point by a double. |
public Point lerp(Point other,double t) | Linearly interpolate between two Points. |
public double distance(Point other) const | Get the distance between two Points. |
public double angle(Point other) const | Get the angle between two Points. |
public Point rotate(double angle) | Rotate a Point by an angle. |
Members
public double x
x value
public double y
y value
public double theta
theta value
public inline Point(double X,double Y,double theta)
Create a new Point.
Parameters
-
Xcomponent -
Ycomponent -
thetaheading. Defaults to 0
public inline double getX()
public inline double getY()
public inline double getAngle()
public inline void setX(double Num)
public inline void setY(double Num)
public inline void setAngle(double Ang)
public inline double getCurve()
public inline double getVelocity()
public inline void setCurve(double curve)
public inline void setVelocity(double vel)
public inline void ExportPoint()
public Point operator+(const Point & other)
Parameters
otherother Point
Returns
public Point operator-(const Point & other)
Subtract a Point from this Point.
Parameters
otherother Point
Returns
public double operator*(const Point & other)
Multiply a Point by this Point.
Parameters
otherother Point
Returns
public Point operator*(const double & other)
Multiply a Point by a double.
Parameters
otherdouble
Returns
public Point operator/(const double & other)
Divide a Point by a double.
Parameters
otherdouble
Returns
public Point lerp(Point other,double t)
Linearly interpolate between two Points.
Parameters
-
otherthe other Point -
tt value
Returns
public double distance(Point other) const
Get the distance between two Points.
Parameters
otherthe other Point
Returns
double
public double angle(Point other) const
Get the angle between two Points.
Parameters
otherthe other Point
Returns
double in radians
public Point rotate(double angle)
Rotate a Point by an angle.
Parameters
angleangle in radians
Returns
class xVecLib::robot
class xVecLib::robot
: public xVecLib::control
A class to allow basic control of the robot using the pid class.
This class provides methods for controlling the robot's movement, scoring mechanism, and more.
Summary
| Members | Descriptions |
|---|---|
public double gearRatio | The gear ratio of the robot's drive. |
public double wheelDiameter | The diameter of the robot's wheels. |
public Point odomPose | The pose of the robot. |
public Point odomSpeed | The speed of the robot. |
public Point odomLocalSpeed | The local speed of the robot. |
public robot(pros::MotorGroup * _rightMotors,pros::MotorGroup * _leftMotors,pros::Imu * _imu,pidSettings linearSetting,pidSettings angularSetting,double wheelDiameter,double gearRatio) | Constructor for the robot class. |
public void driveForwardTiles(double tiles) | Drives the Robot forward tiles. |
public void driveForwardInches(double inches) | #### Parameters |
public void driveReverseTiles(double tiles) | Drive the robot in reverse for a given number of tiles. |
public void driveReverseInches(double inches) | Drive the robot in reverse for a given number of inches. |
public void turnRight(double degree) | Turn the robot to the right by the specified degrees. |
public void turnLeft(double degree) | Turn the robot to the left by the specified degrees. |
public void moveToTile(double tileX,double tileY) | Runs the moveTo method, but converts tileX and tileY to the amount of inches they would represent. |
public void addTilePoint(Point tile) | Adds a point in the form of a point object to the moveToPath. |
public void addTilePoint(double tileX,double tileY) | Adds a point in standard (x,y) to moveToPath. |
public void addFieldPoint(double tileX,double tileY) | Adds a point in the (y, x) form to moveToPath. |
public void setDrivePID(pidValue pidVal) | Set the Drive PID object. |
public pidValue getDrivePID() | Get the Drive PID object. |
public void setTurnPID(pidValue pidVal) | Set the Turn PID object. |
public pidValue getTurnPID() | Get the Turn PID object. |
public void setHelperPID(pidValue pidVal) | Set the Helper PID object. |
public pidValue getHelperPID() | Get the Helper PID object. |
public void setSwingPID(pidValue pidVal) | Set the Swing PID object. |
public pidValue getSwingPID() | Get the Swing PID object. |
public void drivePID(double target,double limit) | Drive to a position using PID. |
public void drivePID(double target,bool fixAngle) | Begins the drive PID control loop and fixes the angle to whay it was before the robot moved. |
public Point getPose(bool radians,bool standardPos) | Get the current pose of the robot. |
public void turnPID(double target) | Begins the turn PID control loop. |
public void turnTo(double targetRotation) | Uses PID to turn to a rotation relative to the robot's starting rotation. |
public void updateOdom(void) | Uses the pros::IMU sensor and the motors to calculate the change in angle. |
public void DriveFront(double DriveTargetX,double DriveTargetY) | Drives forward an amount of x and y in a linear form. |
public void DriveBack(double DriveTargetX,double DriveTargetY) | Drives reverse an amount of x and y in a linear form. |
public void setOdomAngle(cAxis odomAxis) | Set the Odom Angle object. |
public void addOdom(odom * newOdom) | Adds an additional tracking wheel, rotaion sensor, or motor to odometry. |
public void helper(double driveX,double driveY) | Runs an advanced PID control loop. |
public void moveTo(double x,double y,double timeOut) | A method that drives to x and y. |
public void moveTo(double x,double y,double limits,moveToParams params) | A method that drives to x and y but overides the behavior of various variables. |
public void moveToBoom(double x,double y,double theta,double lead,double timeOut) | A method that drives to x and y using the boomerang controller. |
public void moveToBoom(double * xr,double * yr,double * thetar,double * leadr,double * timeOutr) | A method that drives to x and y using the boomerang controller. |
public void addPoint(Point NewPoint) | A method that defines the path for the xVecLib::PID::moveToPath method. |
public void moveToPath() | An unfinished method that runs the xVecLib::PID::moveTo method along a predefined path. |
public void setMoveTo(double maxDis,double maxPower,double lowThresh) | Sets the variables of the moveTo method. |
public void printCoords() | Prints the current x, y, and heading of the robot. |
public void clearPath(void) | Clears the path of points used in the moveToPath method. |
public void right_swing(float angle,float oppositeSpeed) | Makes the robot swing to the right. |
public void left_swing(float angle,float oppositeSpeed) | Makes the robot swing to the left. |
public void setPos(double x,double y,double theta) | Sets the robots position. |
public void moveCursor(int x,int y) | Moves the cursor. |
protected pidValue drivePIDv | The PID values for the drive. |
protected pidValue turnPIDv | The PID values for the turn. |
protected pidValue helperPIDv | The PID values for the helper. |
protected pidValue swingPID | The PID values for the swing. |
protected pidSettings lateralSettings | The settings for the lateral PID. |
protected pidSettings angularSettings | The settings for the angular PID. |
protected drawing drawer | The drawing object for the robot. |
protected odom*additionOdom | The sensor object for the robot. |
protected double deltaX | The change in X value of the robot. |
protected double deltaY | The change in Y value of the robot. |
protected pros::MotorGroup * rightMotors | A pointer to the right Motors. |
protected pros::MotorGroup * leftMotors | A pointer to the top left Motors. |
protected pros::Imu * imu | A pointer to the pros::IMU sensor on the robot. |
protected pros::Mutex move | A mutex for the moveTo method. |
Members
public double gearRatio
The gear ratio of the robot's drive.
This is used to calculate the robot's speed
public double wheelDiameter
The diameter of the robot's wheels.
This is used to calculate the robot's speed
public Point odomPose
The pose of the robot.
This is updated in the odometry loop
public Point odomSpeed
The speed of the robot.
This is updated in the odometry loop
public Point odomLocalSpeed
The local speed of the robot.
This is updated in the odometry loop
public robot(pros::MotorGroup * _rightMotors,pros::MotorGroup * _leftMotors,pros::Imu * _imu,pidSettings linearSetting,pidSettings angularSetting,double wheelDiameter,double gearRatio)
Constructor for the robot class.
Parameters
-
_rightMotorsThe motors on the right side of the robot -
_leftMotorsThe motors on the left side of the robot -
_imuThe IMU that provides information about the robot's orientation -
linearSettingThe linear PID values -
angularSettingThe angular PID values -
wheelDiameterThe diameter of the robot's wheel -
gearRatioThe gear ratio of the robot
public void driveForwardTiles(double tiles)
Drives the Robot forward tiles.
Parameters
tilesThe amount of tiles the robot should go.
public void driveForwardInches(double inches)
Parameters
inchesThe amount of inches the robot should go.
This uses the PID::DriveFront method instead of drivePID
public void driveReverseTiles(double tiles)
Drive the robot in reverse for a given number of tiles.
Parameters
tiles- The number of tiles to drive in reverse.
public void driveReverseInches(double inches)
Drive the robot in reverse for a given number of inches.
Parameters
inches- The number of inches to drive in reverse.
public void turnRight(double degree)
Turn the robot to the right by the specified degrees.
Parameters
degreethe degrees to turn the robot to the right
public void turnLeft(double degree)
Turn the robot to the left by the specified degrees.
Parameters
degreethe degrees to turn the robot to the left
public void moveToTile(double tileX,double tileY)
Runs the moveTo method, but converts tileX and tileY to the amount of inches they would represent.
Parameters
-
tileXThe x value of the tile -
tileYThe y value of the tile
public void addTilePoint(Point tile)
Adds a point in the form of a point object to the moveToPath.
Parameters
tile
public void addTilePoint(double tileX,double tileY)
Adds a point in standard (x,y) to moveToPath.
Parameters
-
tileX -
tileY
public void addFieldPoint(double tileX,double tileY)
Adds a point in the (y, x) form to moveToPath.
This is used to give an alternate way to placing points.
Parameters
-
tileX -
tileY
public void setDrivePID(pidValue pidVal)
Set the Drive PID object.
Sets the Drive PID object with the given values.
Parameters
pidValThe values to set
public pidValue getDrivePID()
Get the Drive PID object.
Gets the current Drive PID object.
Returns
public void setTurnPID(pidValue pidVal)
Set the Turn PID object.
Sets the Turn PID object with the given values.
Parameters
pidVal
public pidValue getTurnPID()
Get the Turn PID object.
Gets the current Turn PID object.
Returns
public void setHelperPID(pidValue pidVal)
Set the Helper PID object.
Sets the Helper PID object with the given values.
Parameters
pidVal
public pidValue getHelperPID()
Get the Helper PID object.
Gets the current Helper PID object.
Returns
public void setSwingPID(pidValue pidVal)
Set the Swing PID object.
Sets the Swing PID object with the given values.
Parameters
pidVal
public pidValue getSwingPID()
Get the Swing PID object.
Gets the current Swing PID object.
Returns
public void drivePID(double target,double limit)
Drive to a position using PID.
Drives the robot to a position using the PID control loop. The PID values set using setSwingPID() are used to control the movement. The target parameter is the position to move to. The limit parameter is the amount of time in milliseconds to allow for the movement. If the limit is set to 0, then the movement will continue until the target is reached.
Parameters
-
targetThe position to move to -
limitThe amount of time to allow for the movement in seconds
public void drivePID(double target,bool fixAngle)
Begins the drive PID control loop and fixes the angle to whay it was before the robot moved.
Parameters
-
targetThe target value for the drive PID control loop in inches. -
fixAngleTrue means the robot will fix the Angle, false will not
public Point getPose(bool radians,bool standardPos)
Get the current pose of the robot.
Gets the current pose of the robot. The pose is returned as a Point object containing the X and Y coordinates of the robot. If radians is true, the angle is returned in radians, otherwise degrees. If standardPos is true, the X and Y coordinates are converted to standard coordinates.
Parameters
-
radiansTrue means return the angle in radians, false means degrees -
standardPosTrue means convert the coordinates to standard coordinates
Returns
Point containing the X and Y coordinates and the angle of the robot
public void turnPID(double target)
Begins the turn PID control loop.
Parameters
targetThe target value for the turn PID control loop in degrees.
public void turnTo(double targetRotation)
Uses PID to turn to a rotation relative to the robot's starting rotation.
Parameters
targetRotationThe rotation to turn to
public void updateOdom(void)
Uses the pros::IMU sensor and the motors to calculate the change in angle.
This is one of the most important methods and must be executed for any method that requires drawing
public void DriveFront(double DriveTargetX,double DriveTargetY)
Drives forward an amount of x and y in a linear form.
In otherwords, It drives forward the amount of X, forward the amount of Y
Parameters
-
DriveTargetX -
DriveTargetY
public void DriveBack(double DriveTargetX,double DriveTargetY)
Drives reverse an amount of x and y in a linear form.
In otherwords, It drives backward the amount of X, forward the amount of Y
Parameters
-
DriveTargetX -
DriveTargetY
public void setOdomAngle(cAxis odomAxis)
Set the Odom Angle object.
Parameters
odomAxis
public void addOdom(odom * newOdom)
Adds an additional tracking wheel, rotaion sensor, or motor to odometry.
Parameters
newOdom
public void helper(double driveX,double driveY)
Runs an advanced PID control loop.
Parameters
-
driveX -
driveY
public void moveTo(double x,double y,double timeOut)
A method that drives to x and y.
Of all the methods so far created, this is both the most tested and accurate
x and y are in inches
Parameters
-
x -
y -
timeOutDefaults to 0
public void moveTo(double x,double y,double limits,moveToParams params)
A method that drives to x and y but overides the behavior of various variables.
Of all the methods so far created, this is both the most tested and accurate
x and y are in inches
Parameters
-
x -
y -
limits -
params
public void moveToBoom(double x,double y,double theta,double lead,double timeOut)
A method that drives to x and y using the boomerang controller.
Parameters
-
xThe x coordinate of the target -
yThe y coordinate of the target -
thetaThe angle of the target -
leadThe lead of the boomerang controller -
timeOutThe time to wait for the robot to reach the target
public void moveToBoom(double * xr,double * yr,double * thetar,double * leadr,double * timeOutr)
A method that drives to x and y using the boomerang controller.
Parameters
-
xA pointer to the x coordinate of the target -
yA pointer to the y coordinate of the target -
thetaA pointer to the angle of the target -
leadA pointer to the lead of the boomerang controller -
timeOutrA pointer to the time to wait for the robot to reach the target
public void addPoint(Point NewPoint)
A method that defines the path for the xVecLib::PID::moveToPath method.
Parameters
[Point](#classx_vec_lib_1_1_point)NewPoint
public void moveToPath()
An unfinished method that runs the xVecLib::PID::moveTo method along a predefined path.
The path is defined by points inserted using the xVecLib::PID::addPoint method
public void setMoveTo(double maxDis,double maxPower,double lowThresh)
Sets the variables of the moveTo method.
Parameters
maxDisThe distance that the robot will start fixing turns
The maxDis variable is poorly coded in general and WILL be redone in a future release
Parameters
-
maxPowerThe maxPower of the robot -
lowThreshThe smallest distance that it can stop, defaults to 12
public void printCoords()
Prints the current x, y, and heading of the robot.
public void clearPath(void)
Clears the path of points used in the moveToPath method.
public void right_swing(float angle,float oppositeSpeed)
Makes the robot swing to the right.
Parameters
-
angleThe angle to swing -
oppositeSpeedThe speed of the opposite side of the robot
public void left_swing(float angle,float oppositeSpeed)
Makes the robot swing to the left.
Parameters
-
angleThe angle to swing -
oppositeSpeedThe speed of the opposite side of the robot
public void setPos(double x,double y,double theta)
Sets the robots position.
Parameters
-
x -
y -
theta
public void moveCursor(int x,int y)
Moves the cursor.
Parameters
-
x -
y
protected pidValue drivePIDv
The PID values for the drive.
These values are set with xVecLib::PID::setDrivePID
protected pidValue turnPIDv
The PID values for the turn.
These values are set with xVecLib::PID::setTurnPID
protected pidValue helperPIDv
The PID values for the helper.
These values are set with xVecLib::PID::setHelperPID
protected pidValue swingPID
The PID values for the swing.
This value is not currently used in the code
protected pidSettings lateralSettings
The settings for the lateral PID.
These values are set with xVecLib::PID::setLateralSettings
protected pidSettings angularSettings
The settings for the angular PID.
These values are set with xVecLib::PID::setAngularSettings
protected drawing drawer
The drawing object for the robot.
This is used to draw lines on the Field object
protected odom*additionOdom
The sensor object for the robot.
This is used to read the sensors on the robot
protected double deltaX
The change in X value of the robot.
This is updated in the odometry loop
protected double deltaY
The change in Y value of the robot.
This is updated in the odometry loop
protected pros::MotorGroup * rightMotors
A pointer to the right Motors.
protected pros::MotorGroup * leftMotors
A pointer to the top left Motors.
protected pros::Imu * imu
A pointer to the pros::IMU sensor on the robot.
This is required for odometry
protected pros::Mutex move
A mutex for the moveTo method.
This is used to prevent multiple threads from running the moveTo method simultaneously
struct xVecLib::odom
A struct for odom devices This includes encoders, rotaion sensors, motor groups, and motors.
Summary
| Members | Descriptions |
|---|---|
public pros::MotorGroup * motors | |
public pros::adi::Encoder * encoder | |
public pros::Rotation * rotation | |
public pros::Motor * motor | |
public inline odom(double _gearRatio,double _wheelDiameter,pros::Motor * _motor) | |
public inline odom(pros::adi::Encoder * encoder,float wheelDiameter,float distance,float gearRatio) | |
public inline odom() | |
public inline odom(pros::Rotation * rotation,float wheelDiameter,float distance,float gearRatio) | Create a new tracking wheel. |
public inline odom(pros::MotorGroup * motors,float wheelDiameter,float gearRatios) | Create a new tracking wheel. |
public inline void reset() | |
public inline double getDistanceTraveled() | |
public inline float getOffset() | Get the offset of the tracking wheel from the center of rotation. |
public inline int getType() | Get the type of tracking wheel. |
Members
public pros::MotorGroup * motors
public pros::adi::Encoder * encoder
public pros::Rotation * rotation
public pros::Motor * motor
public inline odom(double _gearRatio,double _wheelDiameter,pros::Motor * _motor)
public inline odom(pros::adi::Encoder * encoder,float wheelDiameter,float distance,float gearRatio)
public inline odom()
public inline odom(pros::Rotation * rotation,float wheelDiameter,float distance,float gearRatio)
Create a new tracking wheel.
Parameters
-
encoderthe v5 rotation sensor to use -
wheelDiameterthe diameter of the wheel -
distancedistance between the tracking wheel and the center of rotation in inches -
gearRatiogear ratio of the tracking wheel, defaults to 1
public inline odom(pros::MotorGroup * motors,float wheelDiameter,float gearRatios)
Create a new tracking wheel.
Parameters
-
motorsthe motor group to use -
wheelDiameterthe diameter of the wheel -
gearRatiothe gear ratio of the drivetrain, defaults to 1
public inline void reset()
public inline double getDistanceTraveled()
public inline float getOffset()
Get the offset of the tracking wheel from the center of rotation.
Returns
float offset in inches
public inline int getType()
Get the type of tracking wheel.
Returns
int - 1 if motor group, 0 otherwise
struct xVecLib::moveToParams
struct containing the moveTo params
Summary
| Members | Descriptions |
|---|---|
public bool noSlowApproach | Boolean representing if the robot should slow down as approachig the target, as apposed of a sudden stop. |
public bool doEndAngle | Enables the endAngle fix, if enabled the endAngle parameter must also be set. |
public bool noInitialFIx | Disables the initial turn fix. This speeds up the method but may not be as accurate. |
public bool backwards | Drives and turns reverse from what It would. In otherwords, it goes backwards to the point. |
public double maxSpeed | Represents the max speed of the robot. |
public double minSpeed | Represents the min speed of the robot. |
public double endAngle | Paired with the doEndAngle, represents the endAngle in degrees. |
public bool useNewSlowApproach | A boolean representing if the robo-t should use the new slow approach. |
Members
public bool noSlowApproach
Boolean representing if the robot should slow down as approachig the target, as apposed of a sudden stop.
public bool doEndAngle
Enables the endAngle fix, if enabled the endAngle parameter must also be set.
public bool noInitialFIx
Disables the initial turn fix. This speeds up the method but may not be as accurate.
public bool backwards
Drives and turns reverse from what It would. In otherwords, it goes backwards to the point.
public double maxSpeed
Represents the max speed of the robot.
public double minSpeed
Represents the min speed of the robot.
public double endAngle
Paired with the doEndAngle, represents the endAngle in degrees.
public bool useNewSlowApproach
A boolean representing if the robo-t should use the new slow approach.
struct xVecLib::pidSettings
Summary
| Members | Descriptions |
|---|---|
public float kP | Proportional. |
public float kI | |
public float kD | |
public float windupRange | |
public float smallError | |
public float smallErrorTimeout | |
public float largeError | |
public float largeErrorTimeout | |
public float slew | |
public inline pidSettings(float kP,float kI,float kD,float windupRange,float smallError,float largeError,float slew) | The constants are stored in a struct so that they can be easily passed to the control/robot classes |
Members
public float kP
Proportional.
public float kI
public float kD
public float windupRange
public float smallError
public float smallErrorTimeout
public float largeError
public float largeErrorTimeout
public float slew
public inline pidSettings(float kP,float kI,float kD,float windupRange,float smallError,float largeError,float slew)
The constants are stored in a struct so that they can be easily passed to the control/robot classes
Parameters
-
kPProportional -
kIIntegral -
kDDerivative -
windupRangethe range of the windup, used as max I -
smallErrorthe error at which the robot begins to stop -
largeErrorthe error at which the robot begins to slow -
slewthe slew rate of the robot's drive
struct robotAccess::coordinate
A simple struct to represent a coordinate.
This is just a simple struct, and is not part of the library
Summary
| Members | Descriptions |
|---|---|
public double x | The X coordinate |
public double y | The Y coordinate |
Members
public double x
The X coordinate
public double y
The Y coordinate
struct pidValue
Struct to hold PID values.
This struct holds PID values for a single PID controller. It also has some other values that are used in the PID loop, such as the output of the previous iteration and the integral of the error.
Summary
| Members | Descriptions |
|---|---|
public double P | The proportional value. |
public double I | The integral value. |
public double D | The derivative value. |
public float goal | The goal value. |
public float timeOut | The time out. |
public double windupRange | The maximum integral value. |
public bool signFlipReset | Reset integral if sign of error changes. |
public double integral | The integral of the error. |
public double prevError | The error of the previous iteration. |
public double itError | The integral of the error divided by the goal. |
public double traveled | The traveled distance. |
public inline pidValue() | Constructor. |
public inline pidValue(double vgoal,double vtimeOut,double vP,double vI,double vD) | Constructor with all values. |
public inline pidValue(double kP,double kI,double kD,double windupRange,bool signFlipReset) | Constructor with windup range and sign flip reset. |
public inline double update(const double error) | Update the PID loop. |
public inline void reset() | Reset the integral to zero. |
public inline bool is_settled() | Check if the PID loop is settled. |
Members
public double P
The proportional value.
public double I
The integral value.
public double D
The derivative value.
public float goal
The goal value.
public float timeOut
The time out.
public double windupRange
The maximum integral value.
public bool signFlipReset
Reset integral if sign of error changes.
public double integral
The integral of the error.
public double prevError
The error of the previous iteration.
public double itError
The integral of the error divided by the goal.
public double traveled
The traveled distance.
public inline pidValue()
Constructor.
public inline pidValue(double vgoal,double vtimeOut,double vP,double vI,double vD)
Constructor with all values.
Parameters
-
vgoalThe goal value -
vtimeOutThe time out -
vPThe proportional value -
vIThe integral value -
vDThe derivative value
public inline pidValue(double kP,double kI,double kD,double windupRange,bool signFlipReset)
Constructor with windup range and sign flip reset.
Parameters
-
kPThe proportional value -
kIThe integral value -
kDThe derivative value -
windupRangeThe maximum integral value -
signFlipResetReset integral if sign of error changes
public inline double update(const double error)
Update the PID loop.
Parameters
errorThe error value
Returns
The output of the PID loop
public inline void reset()
Reset the integral to zero.
public inline bool is_settled()
Check if the PID loop is settled.
Returns
True if the loop is settled
struct robotAccess
The robotAccess struct allows PID and other code in xVecLib to gain access to the robot variables.
Summary
| Members | Descriptions |
|---|---|
public double robotX | Represents the current robot X |
public double robotY | Represents the current robot Y |
public double robotAngle | Represents the current robot Angle in degrees |
public double Theta | Represents the current robot Angle in radians |
public roboColor robotColor | Represents the Robot Color. Only used in the drawing class and will be combined with the robot class |
public xVecLib::cAxis robotAxis | Represents the starting axis of the robot. Only set it to Y as X isn't finished yet. See xVecLib::PID::setOdomAngle |
public inline robotAccess() | Constructor that sets the position to 0,0. |
public inline robotAccess(double posX,double posY) | Constructor that sets the position to the given coordinates. |
public inline robotAccess(coordinate coord) | Constructor that sets the position to the given coordinates. |
public inline void set(double posX,double posY) | Sets the position to the given coordinates. |
public inline void set(coordinate coord) | Sets the position to the given coordinates. |
public inline coordinate get() | Gets the position as a coordinate. |
public inline xVecLib::Point getPoint() |
Members
public double robotX
Represents the current robot X
public double robotY
Represents the current robot Y
public double robotAngle
Represents the current robot Angle in degrees
public double Theta
Represents the current robot Angle in radians
public roboColor robotColor
Represents the Robot Color. Only used in the drawing class and will be combined with the robot class
public xVecLib::cAxis robotAxis
Represents the starting axis of the robot. Only set it to Y as X isn't finished yet. See xVecLib::PID::setOdomAngle
public inline robotAccess()
Constructor that sets the position to 0,0.
public inline robotAccess(double posX,double posY)
Constructor that sets the position to the given coordinates.
Parameters
-
posXThe X coordinate -
posYThe Y coordinate
public inline robotAccess(coordinate coord)
Constructor that sets the position to the given coordinates.
Parameters
coordThe coordinate
public inline void set(double posX,double posY)
Sets the position to the given coordinates.
Parameters
-
posXThe X coordinate -
posYThe Y coordinate
public inline void set(coordinate coord)
Sets the position to the given coordinates.
Parameters
coordThe coordinate
public inline coordinate get()
Gets the position as a coordinate.
Returns
The coordinate
public inline xVecLib::Point getPoint()
Generated by Moxygen