Skip to main content

Tank Chassis

warning

The coordinates needs to be in (inches), orientation in (degrees), velocity units in (inches/seconds) and the acceleration units in (inches/seconds2).

Otherwise, the code will not work as expected.

Constructors

No Odometry

TankChassis constructor without odometry.

 TankChassis(tank_odom_e_t odom_config,
const std::initializer_list<std::int8_t>& left_side_ports,
const std::initializer_list<std::int8_t>&right_side_ports,
const char gyro_port, const pros::motor_gearset_e_t gearset,
float wheel_diameter, float gear_ratio);
Parameters
odom_configWhat odometry configuration the user want. (This constructor is designated for chassis without odometry system).
left_side_portsA vector/list of the left motors ports of the drivetrain (using a negative number will reverse it!).
right_side_portsA vector/list of the right motors ports of the drivetrain (using a negative number will reverse it!).
gyro_portThe IMU port.
gearsetWhat is the cartridge of you drivetrain (blue,green, red)?
wheel_diameterWhat is the side of the drivetrain wheels ?
gear_ratioWhat is the gear ratio (Is the result of Driven/Driving, Drive:Driving)?

ADI odometry

TankChassis constructor with odometry using ADI encoders (The red ones).

 TankChassis(tank_odom_e_t odom_config, 
const std::initializer_list<std::int8_t>& left_side_ports,
const std::initializer_list<std::int8_t>&right_side_ports,
const char gyro_port, const pros::motor_gearset_e_t gearset,
float wheel_diameter,
float gear_ratio,
const std::vector<int>& Encoder_Forward_Tracker_ports,
const float Forward_Tracker_diameter,
const float Forward_Tracker_distance_to_center,
const std::vector<int>&Encoder_SideWays_Tracker_ports,
const float SideWays_Tracker_wheel_diameter,
const float SideWays_Tracker_distance_to_center);
Parameters
odom_configwhat odometry configuration the user want. (This constructor is designated for chassis with ADI encoder odometry).
left_side_portsA vector/list of the left motors ports of the drivetrain (using a negative number will reverse it!).
right_side_portsA vector/list of the right motors ports of the drivetrain (using a negative number will reverse it!).
gyro_portThe IMU port.
gearsetWhat is the cartridge of you drivetrain (blue,green, red)?
wheel_diameterWhat is the side of the drivetrain wheels in inches?
gear_ratioWhat is the gear ratio (Is the result of Driven/Driving, Drive:Driving)?
Encoder_Forward_Tracker_portsForward ADI ENCODER PORTS (using a negative number will reverse it!)!
Forward_Tracker_diameterThe wheel diameter of your forward tracker (must to be in inches).
Forward_Tracker_distance_to_centerthe distance that exist between the forward tracker and the robot center point (must to be in inches).
Encoder_SideWays_Tracker_ports//SIDEWAYS ADI ENCODER PORTS (using a negative number will reverse it!), setting -1,-1 would cancel the tracker!
Sideways_Tracker_diameterThe wheel diameter of your sideways tracker (must to be in inches).
Sidways_Tracker_distance_to_centerthe distance that exist between the sideways tracker and the robot center point (must to be in inches).

V5 Rotation Sensor Odometry

TankChassis constructor with odometry using the V5 rotation sensors.

 TankChassis(tank_odom_e_t odom_config, 
const std::initializer_list<std::int8_t>& left_side_ports,
const std::initializer_list<std::int8_t>&right_side_ports,
const char gyro_port, const pros::motor_gearset_e_t gearset,
float wheel_diameter,
float gear_ratio,
const int Rotation_Forward_Tracker_port,
const float Forward_Tracker_diameter,
const float Forward_Tracker_distance_to_center,
const int Rotation_SideWays_Tracker_port,
const float SideWays_Tracker_wheel_diameter,
const float SideWays_Tracker_distance_to_center);
Parameters
odom_configwhat odometry configuration the user want. (This constructor is designated for chassis with ADI encoder odometry).
left_side_portsA vector/list of the left motors ports of the drivetrain (using a negative number will reverse it!).
right_side_portsA vector/list of the right motors ports of the drivetrain (using a negative number will reverse it!).
gyro_portThe IMU port.
gearsetWhat is the cartridge of you drivetrain (blue,green, red)?
wheel_diameterWhat is the side of the drivetrain wheels ?
gear_ratioWhat is the gear ratio (Is the result of Driven/Driving, Drive:Driving)?
Rotation_Forward_Tracker_portForward V5 ROTATION SENSOR PORT (using a negative number will reverse it!)!
Forward_Tracker_diameterThe wheel diameter of your forward tracker (must to be in inches).
Forward_Tracker_distance_to_centerThe distance that exist between the forward tracker and the robot center point (must to be in inches).
Rotation_SideWays_Tracker_portSideways V5 ROTATION SENSOR PORT (using a negative number will reverse it!)!,setting 0 would cancel the tracker!
Sideways_Tracker_diameterThe wheel diameter of your sideways tracker (must to be in inches).
Sidways_Tracker_distance_to_centerThe distance that exist between the sideways tracker and the robot center point (must to be in inches).

PID Functions

set_drive_constants()

Sets the drive_pid constants for the Drive PID controller.

 void set_drive_constants(float kp , float ki , float kd, float max, float scale, float integral_power_limit,float derivative_tolerance); 
Parameters
kpProportional constant.
kiIntegral constant.
kdDerivative constant.
maxPID max output.
scalePID scale.
integral_power_limitThe Integral_power_limit.
derivative_toleranceHow much the derivative would affect?.

set_drive_exit_conditions()

Sets the drive_pid exit conditions, conditions that would make that Drive PID controller stops

void set_drive_exit_conditions(float error_tolerance, float jump_time_msec, float stop_time_msec); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

set_drive_scale()

Sets the drive_pid scale.

void set_drive_scale(const float scale); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

set_turn_constants()

Sets the turn_pid constants for the Turn PID controller.

 void set_turn_constants(float kp , float ki , float kd, float max, float scale, float integral_power_limit,float derivative_tolerance); 
Parameters
kpProportional constant.
kiIntegral constant.
kdDerivative constant.
maxPID max output.
scalePID scale.
integral_power_limitThe Integral_power_limit.
derivative_toleranceHow much the derivative would affect?.

set_turn_exit_conditions()

Sets the turn_pid exit conditions, conditions that would make that Turn PID controller stops

void set_turn_exit_conditions(float error_tolerance, float jump_time_msec, float stop_time_msec); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

set_turn_scale()

Sets the turn_pid scale.

void set_turn_scale(const float scale); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

set_swing_constants()

Sets the swing_pid constants for the Swing PID controller.

 void set_swing_constants(float kp , float ki , float kd, float max, float scale, float integral_power_limit,float derivative_tolerance); 
Parameters
kpProportional constant.
kiIntegral constant.
kdDerivative constant.
maxPID max output.
scalePID scale.
integral_power_limitThe Integral_power_limit.
derivative_toleranceHow much the derivative would affect?.

set_swing_exit_conditions()

Sets the swing_pid exit conditions, conditions that would make that Swing PID controller stops

void set_swing_exit_conditions(float error_tolerance, float jump_time_msec, float stop_time_msec); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

set_swing_scale()

Sets the swing_pid scale.

void set_swing_scale(const float scale); 
Parameters
error_toleranceThe error tolerance for the controller.
jump_time_msecThe jump time limit in milliseconds.
stop_time_msecThe stop time limit in milliseconds. If more than this time elapses,the PID controller output will be forced to zero.

Motion Functions

Some motion functions uses okapi units to give more variety.

To learn more about okapi units, check here.

move_velocity()

Sets the velocity for the motors chassis.

note

This velocity corresponds to different actual speeds depending on the gearset used for the chassis. This results in a range of +-100 for E_MOTOR_GEARSET_36, +-200 for E_MOTOR_GEARSET_18, and +-600 for E_MOTOR_GEARSET_6. The velocity is held with PID to ensure consistent speed, as opposed to setting the motor's voltage.

void move_velocity(const int rpm); 
Parameters
rpmThe new motors chassis velocity from +-100, +-200, or +-600 depending on the motor's gearset

Sets the velocity for the motor chassis (Leftside or Rightside)

void move_velocity(const int left_rpm, const int right_rpm); 
Parameters
left_rpmThe left_side motors chassis velocity from +-100, +-200, or +-600 depending on the motor's gearset
right_rpmThe right_side motors chassis velocity from +-100, +-200, or +-600 depending on the motor's gearset

move_voltage()

Sets the output voltage for the motors chassis from -12000 to 12000 in millivolts.

void move_voltage(const int voltage_mv);
Parameters
voltage_mvThe new voltage value from -12000 to 12000 millivolts.

Sets the output voltage for the motors chassis sides (LEFT SIDE AND RIGHT SIDE) from -12000 to 12000 in millivolts.

void move_voltage(const int left_voltage_mv, const int right_voltage_mv);
Parameters
left_voltage_mvThe new voltage value from -12000 to 12000 millivolts for the left side.
right_voltage_mvThe new voltage value from -12000 to 12000 millivolts for the right side.

move()

Sets the voltage for the motors chassis from -127 to 127.

This is designed to map easily to the input from the controller's analog stick for simple opcontrol use.

void move(const int voltage); 
Parameters
voltageThe new motors chassis voltage from -127 to 127.

Sets the voltage for the motors chassis sides (left and right sides) from -127 to 127.

This is designed to map easily to the input from the controller's analog stick for simple opcontrol use.

void move(const int left_voltage, const int right_voltage); 
Parameters
left_voltageThe new left side motors chassis voltage from -127 to 127.
right_voltageThe new right side motors chassis voltage from -127 to 127.

drive_to_point()

Drives the robot from a starting point to a target point. Different versions of this function are available below.

note

The robot MUST to be facing the target point with the front or back side of the chassis.

Using custom PID controllers and inches units.

Drives the robot from a starting point to a target point using custom PID controller (Created for the user) and in inches units.

void drive_to_point(PID& drive_controller, PID& turn_controller, std::vector<double> target, bool reverse); 
Parameters
drive_controllerA PID controller designated for controlling the forward and backward movements of the robot.
turn_controllerA PID controller designated for turns.
targetThe target point {x,y} in inches.
reverseThe direction. true if you want to go backwards, false if you want to go forward.

Using custom PID controllers and okapi units.

Drives the robot from a starting point to a target point using custom PID controller (Created for the user) using okapi units.

void drive_to_point(PID& drive_controller, PID& turn_controller, std::vector<okapi::QLength> target, bool reverse); 
Parameters
drive_controllerA PID controller designated for controlling the forward and backward movements of the robot.
turn_controllerA PID controller designated for turns.
targetThe target point {x,y} in okapi units,for example could be in inches, centimeters, meters, etc.
reverseThe direction. true if you want to go backwards, false if you want to go forward.

Using drive_pid , turn_pid and inches units.

Drives the robot from a starting point to a target point using the Drive and Turn PID .

void drive_to_point(std::vector<double>target, bool reverse); 
Parameters
targetThe target point {x,y} in inches
reverseThe direction. true if you want to go backwards, false if you want to go forward.

Using drive_pid , turn_pid and okapi units.

Drives the robot from a starting point to a target point using the Drive and Turn PID using okapi units.

void drive_to_point(std::vector<okapi::QLength> target, bool reverse); 
Parameters
targetThe target point {x,y} in okapi units for example could be in inches, centimeters, meters, etc.
reverseThe direction. true if you want to go backwards, false if you want to go forward.

follow_path()

Drives the robot to follow a pre-computaded path using pure pursuit.

Different versions of this function are available below.

tip

You can see more information about pure pursuit here

Using custom PID.

Drives the robot to follow a pre-computaded path using PID controllers created for the user.

 void follow_path(Path &path, PID& drive_controller,PID&turn_controller, float look_ahead_distance); 

Parameters
pathA desired path created by the Path class.
drive_controllerA PID controller designated for controlling the forward and backward movements of the robot.
turn_controllerA PID controller designated for turns.
look_ahead_distancThe look ahead distance. It its important for the pure pursuit calculations see more information here.

Using drive_pid and turn_pid

Drives the robot to follow a pre-computaded path using the Drive and Turn PIDS from tank chassis class.

 void follow_path(Path&path,float look_ahead_distance);
Parameters
pathA desired path created by the Path class.
look_ahead_distancThe look ahead distance. It its important for the pure pursuit calculations see more information here.

move_with_motion_profile()

Drives the robot using a trapezoidal profile.

 void move_with_motion_profile(TrapezoidalProfile& profile); 
Parameters
profileThe trapezoidal profile.

raw_drive_distance()

Drives the robot to a certain distance and velocity in RPM, using the PROS move_absolute function.

note

A positive distance means that the robot needs to move forward, while a negative distance means that the robot needs to move backwards.

Different versions of this function are available below.

Using inches.

note

The user needs to set how many inches the robot would move.

 void raw_drive_distance(double distance, const int vel_rpm);  
Parameters
distanceHow many inches do you want that the robot moves? (with a negative distance your robot would go in backwards)
vel_rpmWhat would be the drive base motors velocity in RPM?

Using okapi units.

note

The user needs to set how many distance the robot would move.

 void raw_drive_distance(const okapi::QLength distance, const int vel_rpm); 
Parameters
distanceHow much distance the robot would move?, Using okapi units (with a negative distance your robot would go in backwards).
vel_rpmWhat would be the drive base motors velocity in RPM?

drive_distance()

Drives the robot to a specified distance using PID controllers.

note

The function will block the program execution until it completes. Once finished, the program will resume and continue running subsequent lines of code.

Different versions of this function are available below.

Using custom PIDs and units of inches and degrees.

This function controls the robot to move a certain distance using a user-defined PID controller for forward and backward movements, while also maintaining alignment using a separate PID controller for turns.

void drive_distance(PID& drive_control, PID& turn_control, double distance, double target_orientation); 
Parameters
drive_controlA PID controller designated for controlling the forward and backward movements of the robot.
turn_controlA PID controller designated for controlling the turns of the robot.
distanceThe distance in inches that you want the robot to move (with a negative distance your robot would go in backwards).
target_orientationThe target orientation in which you want the robot to stay in degrees.

Using custom PIDs and okapi units.

This function controls the robot to move a certain distance using a user-defined PID controller for forward and backward movements, while also maintaining alignment using a separate PID controller for turns. This functions uses okapi units.

void drive_distance(PID& distance_control, PID& turn_controller, 
const okapi::QLength distance, const okapi::QAngle target_orientation);
Parameters
drive_controlA PID controller designated for controlling the forward and backward movements of the robot.
turn_controlA PID controller designated for controlling the turns of the robot.
distanceThe distance in okapi units (inches,centimeters,tiles,etc) that you want the robot to move (with a negative distance your robot would go in backwards).
target_orientationThe target orientation in which you want the robot to stay in okapi units (radians,degrees).

Using drive_pid , turn_pid and units of inches and degrees.

This function controls the robot to move a certain distance using the drive_pid ,while also maintaining alignment using a turn_pid controller for turns. Using units of inches and degrees.

void drive_distance(const double distance, const double target_orientation);  
Parameters
distanceThe distance in inches that you want the robot to move (with a negative distance your robot would go in backwards).
target_orientationThe target orientation in which you want the robot to stay in degrees

Using drive_pid , turn_pid and okapi units

This function controls the robot to move a certain distance using the drive_pid ,while also maintaining alignment using a turn_pid controller for turns. Using okapi units.

void drive_distance(const okapi::QLength distance, const okapi::QAngle target_orientation); 
Parameters
distanceThe distance in okapi units (inches,centimeters,tiles,etc) that you want the robot to move (with a negative distance your robot would go in backwards).
target_orientationThe target orientation in which you want the robot to stay in okapi units (radians,degrees).

turn_absolute()

Makes the robot turn to a certain orientation using a PID controller.

note

The turning direction is determinated depending of which direction means less travel.

Using custom PID and units of degrees.

 void turn_absolute(PID&turn_control,double target_orientation);
Parameters
turn_controlThe user PID controller.
target_orientationThe target orientation in degrees.

Using custom PID and okapi units.

void turn_absolute(PID& turn_control,okapi::QAngle target_orientation); 
Parameters
turn_controlThe user PID controller.
target_orientationThe target orientation in okapi units.

Using turn_pid and units of degrees

 void turn_absolute(double target_orientation); 

Parameters
target_orientationThe target orientation in degrees.

Using turn_pid and okapi units

 void turn_absolute(okapi::QAngle target_orientation); 

Parameters
target_orientationThe target orientation in okapi units.

turn_relative()

Turns the robot certain number of degrees, positive if the robot needs to turn right or negative if the robot needs to turn left.

note

The turning direction is determinated depending of which direction means less travel.

Using custom PID and units of degrees.

 void turn_relative(PID&turn_control,double degrees);

Parameters
turn_controlThe user PID controller.
degreesHow many degrees would turn?

Using custom PID and okapi units

void turn_relative(PID& turn_control,okapi::QAngle degrees); 

Parameters
turn_controlThe user PID controller.
degreesHow many okapi units would turn?

Using turn_pid and units of degrees

 void turn_relative(double degrees); 

Parameters
degreesHow many degrees would turn?

Using turn_pid and okapi units

 void turn_relative(okapi::QAngle degrees); 

Parameters
degreesHow many okapi units would turn?

swing_turn_absolute()

Makes the robot turn to a certain orientation using a user-defined PID controller, blocking one side of the drive train, making a swing.

note

The turning direction is determinated depending of which direction means less travel.

Using custom PID and units of degrees

void swing_turn_absolute(PID&swing_control, lightning::swing_direction_e_t swing_direction, 
double target_orientation, const int opposide_speed_rpm=0);

Parameters
swing_controlThe user PID controller.
swing_directionWhat side do you want to block?
target_orientationThe target orientation in degrees.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using custom PID and okapi units

 void swing_turn_absolute( PID& swing_control, lightning::swing_direction_e_t swing_direction, 
okapi::QAngle target_orientation, const int opposite_speed_rpm=0);

Parameters
swing_controlThe user PID controller.
swing_directionWhat side do you want to block?
target_orientationThe target orientation in okapi units.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using swing_pid and units of degrees

  void swing_turn_absolute(lightning::swing_direction_e_t swing_direction, double target_orientation, 
const int opposide_speed_rpm=0);

Parameters
swing_directionWhat side do you want to block?
target_orientationThe target orientation in degrees.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using swing_pid and okapi units

   void swing_turn_absolute(lightning::swing_direction_e_t swing_direction, 
const okapi::QAngle target_orientation, const int opposide_speed_rpm=0);

Parameters
swing_directionWhat side do you want to block?
target_orientationThe target orientation in okapi units.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

swing_turn_relative()

Makes the robot turn to a certain amount of degrees using a user-defined PID controller, blocking one side of the drive train, making a swing. if the robot needs to turn right or negative if the robot needs to turn left.

Using custom PID and units of degrees

void swing_turn_relative(PID& swing_control, lightning::swing_direction_e_t swing_direction, 
double degrees, const int opposide_speed_rpm=0);

Parameters
swing_controlThe user PID controller.
swing_directionWhat side do you want to block?
degreeshow many degrees would turn?.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using custom PID and okapi units

void swing_turn_relative(PID& swing_control, lightning::swing_direction_e_t swing_direction, 
okapi::QAngle angle, const int opposide_speed_rpm=0);

Parameters
swing_controlThe user PID controller.
swing_directionWhat side do you want to block?
degreeshow many okapi units would turn?.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using swing_pid and units of degrees

  void swing_turn_relative(lightning::swing_direction_e_t swing_direction, double degrees, const int opposide_speed_rpm=0); 

Parameters
swing_directionWhat side do you want to block?
degreeshow many degrees would turn?.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

Using swing_pid and okapi units

    void swing_turn_relative(lightning::swing_direction_e_t swing_direction, 
okapi::QAngle angle, const int opposide_speed_rpm=0);

Parameters
swing_directionWhat side do you want to block?
degreeshow many okapi units would turn?.
opposide_speed_rpmYou could add power to the blocked side, however is zero by default.

stop()

Stops the chassis.

    void stop(); 


Driver functions

For arcade types, you need to provide one of following configurations:

Arcade configurationsDescription
E_TANK_OP_ARCADE_LEFTLeft stick configuration.
E_TANK_OP_ARCADE_RIGHTRight stick configuration.
E_TANK_OP_ARCADE_DOUBLEDouble stick configuration.

arcade()

Drives the chassis in arcade configuration.

note

The default configuration is with the left joystick.

    void arcade(pros::Controller& control, 
const lightning::tank_op_arcade_e_t arcade = lightning::E_TANK_OP_ARCADE_LEFT ,
const float power_rate=1, const float turn_rate=1);

Parameters
controlThe control.
arcadeThe tank_op_arcade_e_t to set for the chassis.
power_rateThe rate for the forward and backwards movements (Default is 1).
turn_rateThe rate for the right and left turns (Default is 1).

arcade_exponential()

Drives the chassis in an arcade configuration using a smoothing function for more accurate control.

void arcade_exponential(pros::Controller&control, const lightning::tank_op_arcade_e_t arcade, 
int n_x, int n_y);

Parameters
controlThe control.
arcadeThe tank_op_arcade_e_t to set for the chassis.
n_xThe exponential for the joystick x axis.
n_yThe exponential for the joystick y axis.

tank()

Drives the chassis in tank configuration.

   void tank(pros::Controller& control); 

Parameters
controlThe control.

Telemetry Functions

note

The position is recorded in inches.

track_pose()

Tracks and Updates pose. The position and orientation vector (x,y,theta) using odometry.

   void track_pose(); 


set_coordinates

Sets the coordinates for the odometry position system.

   void set_coordinates(const okapi::QLength x, const okapi::QLength y, const okapi::QAngle orientation_deg);

Parameters
xThe x coordinate in okapi unit.
yThe y coordinate in okapi unit.
orientationThe orientation in okapi unit.

set_odometry_rotation()

Sets the odometry rotation for the odometry position system. The odometry rotation is needed for ROTATED configurations like: ADI_TWO_ROTATED_ODOM and ROTATION_TWO_ROTATED_ODOM.

note

For example if your tracking wheels are rotated to -45 degrees, you use set_odometry_rotation(-45);

  void set_odometry_rotation(const double angle_of_rotation_deg); 
Parameters
angle_of_rotation_degThe angle of rotation in degrees.

set_orientation()

Sets the robot´s absolute orientation in degrees.

   void set_orientation(okapi::QAngle current_orientation); 

Parameters
orientationThe orientation in okapi unit.

get_odometry_rotation()

Gets the odometry rotation in degrees.
The odometry rotation is needed for ROTATED configurations like: ADI_TWO_ROTATED_ODOM and ROTATION_TWO_ROTATED_ODOM

   double get_odometry_rotation(); 

Returns: The tracking wheels rotation from the robots center.


get_pose()

Gets the current pose (the position and orientation vector).

   std::vector<double> get_pose(); 

Returns: The pose vector.


get_position()

Gets the current position (x,y)

   std::vector<double> get_pose(); 

Returns: The position vector.


get_x()

Gets the current x coordinate in inches.

    double get_x() const ; 

Returns: The x coordinate in inches.


get_y()

Gets the current y coordinate in inches.

    double get_y() const ; 

Returns: The y coordinate in inches.


get_orientation()

Gets the current orientation (theta) in degrees.

    double get_orientation() const ; 

Returns: The orientation in degrees.


get_ForwardTracker_position()

Gets the forwardtracker position value in inches.

double get_ForwardTracker_position(); 

Returns: The forwardtracker position in inches.


get_SideWays_position()

Gets the Sidewaystracker position value in inches.

double get_SideWays_position(); 

Returns: The sidewaystracker position in inches.


get_average_motors_position_deg()

Gets the drive-train average mposition in degrees.

double get_average_motors_position_deg();

Returns: The average motor position in degrees.


get_left_position_deg()

Gets the left side of the drive-train average position in degrees.

double get_left_position_deg(); 

Returns: The average motor position in degrees.


get_right_position_deg()

Gets the right side of the drive-train average position in degrees.

double get_right_position_deg(); 

Returns: The average motor position in degrees.


get_average_motors_position_inches();

Gets the drive train average position in inches.

double get_average_motors_position_inches();

Returns: The average motor position in inches.


get_left_position_inches();

Gets the left side of the drive train average position in inches.

double get_left_position_inches(); 

Returns: The average motor position in inches.


get_right_position_inches()

Gets the right side of the drive train average position in inches.

double get_right_position_inches(); 

Returns: The average motor position in inches.


get_actual_rpm()

Gets the current average chassis output velocity (RPM) between the left and right sides.

This function calculates and returns the average rotational speed in RPM of the base motors.

note

This velocity is the average of the base motors' output.

double get_actual_rpm(); 

Returns: The average velocity in RPM.


get_actual_velocity()

Gets the current chassis lineal velocity in distance/seconds.

double get_actual_velocity(); 

Returns: The maximum Drive train lineal velocity.


get_current_index()

Get the current index of a path when the robot its following it.

   int get_current_index(); 


reset_odometry()

Resets the position, orientation, tracking wheels value of the robot.

void reset_odometry();


reset_IMU()

Resets the IMU.

void reset_IMU(); 


tare_motors_position()

Tares the integrated encoders from the drive train motors.

void tare_motors_position();


Configuration Functions

set_brake()

Sets the chassis motors brake mode.

void set_brake(const pros::motor_brake_mode_e_t mode); 


set_wheels_diameter()

Sets the chassis wheels diameter in inches.

void set_wheels_diameter(const float _wheels_diameter); 


set_center_distance()

Sets the distance between lateral wheels to the center of rotation in inches.

 void set_center_distance(const float distance); 

Parameters
distanceThe center distance in inches

set_gearing()

Sets the drivetrain cartridge.

void set_gearing(const pros::motor_gearset_e_t gearset);

Parameters
gearsetThe gearset

set_gear_ratio()

Sets the chassis´s gear ratio.

note

speed is equal to = rpm/ gear ratio. And torque is equal to = torque* gear_ratio

void set_gear_ratio(const float _gear_ratio); 

Parameters
_gear_ratioIs the result of Driven/Driving, Drive:Driving

set_max_rpm()

Sets the maximum chassis velocity RPM.

note

May you want to test auto_set_max_actual_vel function to know this value and then set the max actual velocity with this function.

void set_max_rpm(const float _max_rpm=0);

Parameters
_max_rpmThe maximum chassis RPM.

set_max_velocity()

Sets the maximum chassis lineal velocity inches/seconds.

note

May you want to test auto_set_max_actual_vel function to know this value and then set the max actual velocity with this function.

 void set_max_velocity(const float _max_vel=0); 

Parameters
_max_velThe maximum robot velocity.

set_max_accel()

Sets the maximum chassis acceleration distance/seconds 2 .

 void set_max_accel(const float _max_accel=0); 

Parameters
_max_accelThe maximun robot acceleration

get_max_rpm()

Gets maximum robot RPM.

 double get_max_rpm(); 

Returns: The maximum Drive train RPM.


get_max_velocity()

Gets the maximum robot lineal velocity in distance/seconds.

 double get_max_velocity(); 

Returns: The maximum robot lineal velocity.


get_max_accel()

Gets the maximum robot lineal acceleration in distance/seconds 2 ..

 double get_max_accel(); 

Returns: The maximum robot lineal acceleration.


get_wheels_diameter()

Gets the robot wheels diameter in inches.

 float get_wheels_diameter() const ;  

Returns: The robot wheels diameter in inches.


get_center_distance()

Gets the center distance in inches.

  float get_center_distance() const;  

Returns: The robot center distance in inches.


get_gearing()

Gets the robot motors gearing.

note

[0] ->36:1, 100 RPM, Red gear set.

[1] ->18:1, 200 RPM, Green gear set.

[2] -> 6:1, 600 RPM, Blue gear set.

  pros::motor_gearset_e get_gearing() const ; 

Returns: The current internal gear ratio of the motors.


get_encoders_units()

Gets the units for recording position by the chassis motors.

  pros::MotorUnits get_encoders_units(); 

Returns: Motors encoder units.


get_actual_brake()

Gets the current brake mode.

   pros::motor_brake_mode_e_t get_actual_brake(); 

Returns: Motors brake.


get_gear_ratio()

Gets the chassis gear ratio.

  float get_gear_ratio() const ; 

Returns: The result of the division of Driven/Driving.

Auto setters

auto_set_max_velocity_with_position()

Runs a test (your bot would runs in a straight line) to set the maximun real robot lineal velocity.

The linear velocity is calculated using the change in position over time

danger

The function is useful when you want to know the real maximun velocity of your robot- Be careful using this function, if the time is to much your robot may crash with the field.

   void auto_set_max_velocity_with_position(const int time_msec, const float scale); 
Parameters
time_msecThe time in miliseconds that robot would run at maximum velocity to make the math.
scaleThe scale of velocity (.8,.9) would be nice.

autoset_max_vel_accel()

Runs a test (your bot would runs in a straight line) to set the maximun real robot lineal velocity.

The linear velocity and acceleration are calculated using the motors RPMS

danger

The function is useful when you want to know the real maximun velocity of your robot- Be careful using this function, if the time is to much your robot may crash with the field.

   void autoset_max_vel_accel(const int time_msec, const float scale);  
Parameters
time_msecThe time in miliseconds that robot would run at maximum velocity to make the math.
scaleThe scale of velocity (.8,.9) would be nice.

auto_set_max_rpm()

Runs a test (your bot would runs in a straight line) to set the maximun real robot lineal velocity.

danger

The function is useful when you want to know the real maximun velocity of your robot- Be careful using this function, if the time is to much your robot may crash with the field.

   void auto_set_max_rpm(const int time_msec, const float scale); 
Parameters
time_msecThe time in miliseconds that robot would run at maximum velocity to make the math.
scaleThe scale of velocity (.8,.9) would be nice.