diff --git a/docs/Docs/auton_functions.md b/docs/Docs/auton_functions.md index 78150753..7bbf3168 100644 --- a/docs/Docs/auton_functions.md +++ b/docs/Docs/auton_functions.md @@ -69,7 +69,7 @@ Drive chassis ( --- -## set_drive_pid() +## pid_drive_set() Sets the drive to go forward using PID and heading correction. `target` is in inches. `speed` is -127 to 127. It's recommended to keep this at 110. @@ -77,18 +77,18 @@ Sets the drive to go forward using PID and heading correction. `toggle_heading` will disable heading correction when false. **Prototype** ```cpp -void set_drive_pid(double target, int speed, bool slew_on = false, bool toggle_heading = true); +void pid_drive_set(double target, int speed, bool slew_on = false, bool toggle_heading = true); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); - chassis.set_drive_pid(24, 110, true); - chassis.wait_drive(); + chassis.pid_drive_set(24, 110, true); + chassis.drive_wait_exit(); } ``` @@ -96,24 +96,24 @@ void autonomous() { --- -## set_turn_pid() +## pid_turn_set() Sets the drive to turn using PID. `target` is in degrees. `speed` is -127 to 127. **Prototype** ```cpp -void set_turn_pid(double target, int speed); +void pid_turn_set(double target, int speed); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); - chassis.set_turn_pid(90, 110); - chassis.wait_drive(); + chassis.pid_turn_set(90, 110); + chassis.drive_wait_exit(); } ``` @@ -121,28 +121,28 @@ void autonomous() { --- -## set_swing_pid() +## pid_swing_set() Sets the robot to swing using PID. The robot will turn using one side of the drive, either the left or right. `type` is either `ez::LEFT_SWING` or `ez::RIGHT_SWING`. `target` is in degrees. `speed` is -127 to 127. **Prototype** ```cpp -void set_swing_pid(e_swing type, double target, int speed); +void pid_swing_set(e_swing type, double target, int speed); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); - chassis.set_swing_pid(ez::LEFT_SWING, 45, 110); - chassis.wait_drive(); + chassis.pid_swing_set(ez::LEFT_SWING, 45, 110); + chassis.drive_wait_exit(); - chassis.set_swing_pid(ez::RIGHT_SWING, 0, 110); - chassis.wait_drive(); + chassis.pid_swing_set(ez::RIGHT_SWING, 0, 110); + chassis.drive_wait_exit(); } ``` @@ -150,25 +150,25 @@ void autonomous() { --- -## wait_drive() +## drive_wait_exit() Locks the code in place until the drive has settled. This uses the exit conditions from the PID class. **Prototype** ```cpp -void wait_drive(); +void drive_wait_exit(); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); - chassis.set_turn_pid(90, 110); - chassis.wait_drive(); + chassis.pid_turn_set(90, 110); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, 110); - chassis.wait_drive(); + chassis.pid_turn_set(0, 110); + chassis.drive_wait_exit(); } ``` @@ -177,24 +177,24 @@ void autonomous() { -## wait_until() +## drive_wait_distance() Locks the code in place until the drive has passed the input parameter. This uses the exit conditions from the PID class. **Prototype** ```cpp -void wait_until(double target); +void drive_wait_distance(double target); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); - - chassis.set_drive_pid(48, 110); - chassis.wait_until(24); - chassis.set_max_speed(40); - chassis.wait_drive(); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); + + chassis.pid_drive_set(48, 110); + chassis.drive_wait_distance(24); + chassis.max_speed_set(40); + chassis.drive_wait_exit(); } ``` @@ -203,20 +203,20 @@ void autonomous() { -## reset_pid_targets() +## pid_targets_reset() Resets all drive PID targets to 0. **Prototype** ```cpp -void reset_pid_targets(); +void pid_targets_reset(); ``` **Example** ```cpp void autonomous() { - chassis.reset_pid_targets(); // Resets PID targets to 0 - chassis.reset_gyro(); // Reset gyro position to 0 - chassis.reset_drive_sensor(); // Reset drive sensors to 0 - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. + chassis.pid_targets_reset(); // Resets PID targets to 0 + chassis.imu_reset(); // Reset gyro position to 0 + chassis.drive_sensors_reset(); // Reset drive sensors to 0 + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. ez::as::auton_selector.selected_auton_call(); // Calls selected auton from autonomous selector. } @@ -227,25 +227,25 @@ void autonomous() { -## set_angle() +## angle_set() Sets the angle of the robot. This is useful when your robot is setup in at an unconventional angle and you want 0 to be when you're square with the field. **Prototype** ```cpp -void set_angle(double angle); +void angle_set(double angle); ``` **Example** ```cpp void autonomous() { - chassis.reset_pid_targets(); // Resets PID targets to 0 - chassis.reset_gyro(); // Reset gyro position to 0 - chassis.reset_drive_sensor(); // Reset drive sensors to 0 - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. + chassis.pid_targets_reset(); // Resets PID targets to 0 + chassis.imu_reset(); // Reset gyro position to 0 + chassis.drive_sensors_reset(); // Reset drive sensors to 0 + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. - chassis.set_angle(45); + chassis.angle_set(45); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); } ``` @@ -254,25 +254,25 @@ void autonomous() { -## set_max_speed() +## max_speed_set() Sets the max speed of the drive. `speed` an integer between -127 and 127. **Prototype** ```cpp -void set_max_speed(int speed); +void max_speed_set(int speed); ``` **Example** ```cpp void autonomous() { - chassis.reset_gyro(); - chassis.reset_drive_sensor(); - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); - - chassis.set_drive_pid(48, 110); - chassis.wait_until(24); - chassis.set_max_speed(40); - chassis.wait_drive(); + chassis.imu_reset(); + chassis.drive_sensors_reset(); + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); + + chassis.pid_drive_set(48, 110); + chassis.drive_wait_distance(24); + chassis.max_speed_set(40); + chassis.drive_wait_exit(); } ``` @@ -283,7 +283,7 @@ void autonomous() { ## set_pid_constants() *Note: this function was changed with 2.0.1* Set PID constants. Below are the defaults. -`pid` either `&chassis.headingPID`, `&chassis.forward_drivePID`, `&chassis.backward_drivePID`, `&chassis.turnPID`, or `&chassis.swingPID`. +`pid` either `&chassis.pid_heading`, `&chassis.pid_forward_drive`, `&chassis.pid_backward_drive`, `&chassis.pid_turn`, or `&chassis.pid_swing`. `p` proportion constant. `i` integral constant. `d` derivative constant. @@ -296,11 +296,11 @@ void set_pid_constants(PID* pid, double p, double i, double d, double p_start_i) **Example** ```cpp void initialize() { - chassis.set_pid_constants(&chassis.headingPID, 11, 0, 20, 0); - chassis.set_pid_constants(&chassis.forward_drivePID, 0.45, 0, 5, 0); - chassis.set_pid_constants(&chassis.backward_drivePID, 0.45, 0, 5, 0); - chassis.set_pid_constants(&chassis.turnPID, 5, 0.003, 35, 15; - chassis.set_pid_constants(&chassis.swingPID, 7, 0, 45, 0); + chassis.set_pid_constants(&chassis.pid_heading, 11, 0, 20, 0); + chassis.set_pid_constants(&chassis.pid_forward_drive, 0.45, 0, 5, 0); + chassis.set_pid_constants(&chassis.pid_backward_drive, 0.45, 0, 5, 0); + chassis.set_pid_constants(&chassis.pid_turn, 5, 0.003, 35, 15; + chassis.set_pid_constants(&chassis.pid_swing, 7, 0, 45, 0); } ``` @@ -308,19 +308,19 @@ void initialize() { --- -## set_slew_min_power() +## slew_min_power_set() Sets the starting speed for slew, with the ability to have different constants for forward and reverse. Below is the defaults. `fwd` integer between -127 and 127. `rev` integer between -127 and 127. **Prototype** ```cpp -void set_slew_min_power(int fwd, int rev); +void slew_min_power_set(int fwd, int rev); ``` **Example** ```cpp void initialize() { - chassis.set_slew_min_power(80, 80); + chassis.slew_min_power_set(80, 80); } ``` @@ -328,13 +328,13 @@ void initialize() { --- -## set_slew_distance() +## slew_distance_set() Sets the distance the drive will slew for, with the ability to have different constants for forward and reverse. Input is inches. Below is the defaults. `fwd` a distance in inches. `rev` a distance in inches. **Prototype** ```cpp -void set_slew_distance (int fwd, int rev); +void slew_distance_set (int fwd, int rev); ``` **Example** @@ -376,21 +376,21 @@ void initialize() { --- -## set_swing_min() +## swing_min_set() Sets the max power of the drive when the robot is within `start_i`. This only enalbes when `i` is enabled, and when the movement is greater then `start_i`. **Prototype** ```cpp -void set_swing_min(int min); +void swing_min_set(int min); ``` **Example** ```cpp void autonomous() { - chassis.set_swing_min(30); + chassis.swing_min_set(30); - chassis.set_swing_pid(45, 110); - chassis.wait_drive(); + chassis.pid_swing_set(45, 110); + chassis.drive_wait_exit(); } ``` @@ -398,21 +398,21 @@ void autonomous() { --- -## set_turn_min() +## turn_min_set() Sets the max power of the drive when the robot is within `start_i`. This only enalbes when `i` is enabled, and when the movement is greater then `start_i`. **Prototype** ```cpp -void set_turn_min(int min); +void turn_min_set(int min); ``` **Example** ```cpp void autonomous() { - chassis.set_turn_min(30); + chassis.turn_min_set(30); - chassis.set_turn_pid(45, 110); - chassis.wait_drive(); + chassis.pid_turn_set(45, 110); + chassis.drive_wait_exit(); } ``` @@ -420,20 +420,20 @@ void autonomous() { --- -## get_swing_min() +## swing_min_get() Returns swing min. **Prototype** ```cpp -int get_swing_min(); +int swing_min_get(); ``` **Example** ```cpp void autonomous() { - chassis.set_swing_min(30); + chassis.swing_min_set(30); - printf("Swing Min: %i", chassis.get_swing_min()); + printf("Swing Min: %i", chassis.swing_min_get()); } ``` @@ -441,20 +441,20 @@ void autonomous() { --- -## get_turn_min() +## turn_min_get() Returns turn min. **Prototype** ```cpp -int get_turn_min(); +int turn_min_get(); ``` **Example** ```cpp void autonomous() { - chassis.set_turn_min(30); + chassis.turn_min_set(30); - printf("Turn Min: %i", chassis.get_turn_min()); + printf("Turn Min: %i", chassis.turn_min_get()); } ``` @@ -463,7 +463,7 @@ void autonomous() { ## interfered -Boolean that returns true when `wait_drive()` or `wait_until()` exit with velocity or is_over_current. +Boolean that returns true when `drive_wait_exit()` or `drive_wait_distance()` exit with velocity or is_over_current. **Prototype** ```cpp bool interfered = false; @@ -475,13 +475,13 @@ bool interfered = false; for (int i=0; i pto_list); **Example** ```cpp -pros::Motor& intake_l = chassis.left_motors[1]; -pros::Motor& intake_r = chassis.right_motors[1]; +pros::Motor& intake_l = chassis.motors_left[1]; +pros::Motor& intake_r = chassis.motors_right[1]; void initialize() { printf("Check: %i %i\n", chassis.pto_check(intake_l), chassis.pto_check(intake_r))); // This prints 0 0 @@ -124,8 +124,8 @@ void pto_remove(std::vector pto_list); **Example** ```cpp -pros::Motor& intake_l = chassis.left_motors[1]; -pros::Motor& intake_r = chassis.right_motors[1]; +pros::Motor& intake_l = chassis.motors_left[1]; +pros::Motor& intake_r = chassis.motors_right[1]; void initialize() { printf("Check: %i %i\n", chassis.pto_check(intake_l), chassis.pto_check(intake_r))); // This prints 0 0 @@ -149,8 +149,8 @@ void pto_toggle(std::vector pto_list, bool toggle); **Example** ```cpp -pros::Motor& intake_l = chassis.left_motors[1]; -pros::Motor& intake_r = chassis.right_motors[1]; +pros::Motor& intake_l = chassis.motors_left[1]; +pros::Motor& intake_r = chassis.motors_right[1]; pros::ADIDigitalOut pto_intake_piston('A'); bool pto_intake_enabled = false; diff --git a/docs/Docs/set_and_get_drive.md b/docs/Docs/set_and_get_drive.md index e3f64c55..99d1c56a 100644 --- a/docs/Docs/set_and_get_drive.md +++ b/docs/Docs/set_and_get_drive.md @@ -69,21 +69,21 @@ Drive chassis ( # Set Drive -## set_tank() +## tank_set() Sets the drive to voltage. `left` an integer between -127 and 127. `right` an integer between -127 and 127. **Prototype** ```cpp -void set_tank(int left, int right); +void tank_set(int left, int right); ``` **Example** ```cpp void autonomous() { - set_tank(127, 127); + tank_set(127, 127); pros::delay(1000); // Wait 1 second - set_tank(0, 0); + tank_set(0, 0); } ``` @@ -91,12 +91,12 @@ void autonomous() { --- -## set_drive_brake() +## drive_brake_set() Sets brake mode for all drive motors. `brake_type` takes either `MOTOR_BRAKE_COAST`, `MOTOR_BRAKE_BRAKE`, and `MOTOR_BRAKE_HOLD` as parameters. **Prototype** ```cpp -void set_drive_brake(pros::motor_brake_mode_e_t brake_type); +void drive_brake_set(pros::motor_brake_mode_e_t brake_type); ``` **Example** @@ -110,12 +110,12 @@ void initialize() { --- -## set_drive_current_limit() +## drive_current_limit_set() Sets mA limit to the drive. Default is 2500. `mA`input miliamps. **Prototype** ```cpp -void set_drive_current_limit(int mA); +void drive_current_limit_set(int mA); ``` **Example** @@ -131,11 +131,11 @@ void initialize() { # Telemetry -## right_sensor() +## sensor_right() Returns right sensor, either integrated encoder or external encoder. **Prototype** ```cpp -int right_sensor(); +int sensor_right(); ``` **Example** @@ -144,7 +144,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Right Sensor: %i \n", chassis.right_sensor()); + printf("Right Sensor: %i \n", chassis.sensor_right()); pros::delay(ez::util::DELAY_TIME); } @@ -155,11 +155,11 @@ void opcontrol() { --- -## right_velocity() +## velocity_right() Returns integrated encoder velocity. **Prototype** ```cpp -int right_velocity(); +int velocity_right(); ``` **Example** @@ -168,7 +168,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Right Velocity: %i \n", chassis.right_velocity()); + printf("Right Velocity: %i \n", chassis.velocity_right()); pros::delay(ez::util::DELAY_TIME); } @@ -179,11 +179,11 @@ void opcontrol() { --- -## right_mA() +## mA_right() Returns current mA being used. **Prototype** ```cpp -double right_mA(); +double mA_right(); ``` **Example** @@ -192,7 +192,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Right mA: %i \n", chassis.right_mA()); + printf("Right mA: %i \n", chassis.mA_right()); pros::delay(ez::util::DELAY_TIME); } @@ -203,11 +203,11 @@ void opcontrol() { --- -## right_over_current() +## over_current_right() Returns `true` when the motor is over current. **Prototype** ```cpp -bool right_over_current(); +bool over_current_right(); ``` **Example** @@ -216,7 +216,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Right Over Current: %i \n", chassis.right_over_current()); + printf("Right Over Current: %i \n", chassis.over_current_right()); pros::delay(ez::util::DELAY_TIME); } @@ -227,11 +227,11 @@ void opcontrol() { --- -## left_sensor() +## sensor_left() Returns left sensor, either integrated encoder or external encoder. **Prototype** ```cpp -int left_sensor(); +int sensor_left(); ``` **Example** @@ -240,7 +240,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Left Sensor: %i \n", chassis.left_sensor()); + printf("Left Sensor: %i \n", chassis.sensor_left()); pros::delay(ez::util::DELAY_TIME); } @@ -251,11 +251,11 @@ void opcontrol() { --- -## left_velocity() +## velocity_left() Returns integrated encoder velocity. **Prototype** ```cpp -int left_velocity(); +int velocity_left(); ``` **Example** @@ -264,7 +264,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Left Velocity: %i \n", chassis.left_velocity()); + printf("Left Velocity: %i \n", chassis.velocity_left()); pros::delay(ez::util::DELAY_TIME); } @@ -275,11 +275,11 @@ void opcontrol() { --- -## left_mA() +## mA_left() Returns current mA being used. **Prototype** ```cpp -double left_mA(); +double mA_left(); ``` **Example** @@ -288,7 +288,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Left mA: %i \n", chassis.left_mA()); + printf("Left mA: %i \n", chassis.mA_left()); pros::delay(ez::util::DELAY_TIME); } @@ -299,11 +299,11 @@ void opcontrol() { --- -## left_over_current() +## over_current_left() Returns `true` when the motor is over current. **Prototype** ```cpp -bool left_over_current(); +bool over_current_left(); ``` **Example** @@ -312,7 +312,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Left Over Current: %i \n", chassis.left_over_current()); + printf("Left Over Current: %i \n", chassis.over_current_left()); pros::delay(ez::util::DELAY_TIME); } @@ -322,17 +322,17 @@ void opcontrol() { --- -## reset_drive_sensor() +## drive_sensors_reset() Resets integrated encoders and trackers if applicable. **Prototype** ```cpp -void reset_drive_sensor(); +void drive_sensors_reset(); ``` **Example** ```cpp void initialize() { - chassis.reset_drive_sensor(); + chassis.drive_sensors_reset(); } ``` @@ -340,17 +340,17 @@ void initialize() { --- -## reset_gyro() +## imu_reset() Sets current gyro position to parameter, defaulted to 0. **Prototype** ```cpp -void reset_gyro(double new_heading = 0); +void imu_reset(double new_heading = 0); ``` **Example** ```cpp void initialize() { - chassis.reset_gyro(); + chassis.imu_reset(); } ``` @@ -358,11 +358,11 @@ void initialize() { --- -## get_gyro() +## imu_get() Gets IMU. **Prototype** ```cpp -double get_gyro(); +double imu_get(); ``` **Example** @@ -371,7 +371,7 @@ void opcontrol() { while (true) { chassis.tank(); - printf("Gyro: %f \n", chassis.get_gyro()); + printf("Gyro: %f \n", chassis.imu_get()); pros::delay(ez::util::DELAY_TIME); } diff --git a/docs/Docs/user_control.md b/docs/Docs/user_control.md index 32e208cc..a02cdc19 100644 --- a/docs/Docs/user_control.md +++ b/docs/Docs/user_control.md @@ -139,7 +139,7 @@ void opcontrol() { ## initialize() -Runs `init_curve_sd()` and `imu_calibrate()`. +Runs `curve_init_sd()` and `imu_calibrate()`. **Prototype** ```cpp void Drive::initialize(); @@ -156,17 +156,17 @@ void initialize() { --- -## init_curve_sd() +## curve_init_sd() Sets the left/right curve constants to what's on the sd card. If the sd card is empty, creates needed files. **Prototype** ```cpp -void init_curve_sd(); +void curve_init_sd(); ``` **Example** ```cpp void initialize() { - chassis.init_curve_sd(); + chassis.curve_init_sd(); } ``` @@ -180,7 +180,7 @@ Sets the left/right curve defaults and saves new values to the sd card. `right` right input curve. **Prototype** ```cpp -void set_curve_default(double left, double right); +void curve_set_default(double left, double right); ``` **Example** @@ -194,18 +194,18 @@ void initialize() { --- -## set_active_brake() +## active_brake_set() Active brake runs a P loop on the drive when joysticks are within their threshold. `kp` proportional constant for drive. **Prototype** ```cpp -void set_active_brake(double kp); +void active_brake_set(double kp); ``` **Example** ```cpp void initialize() { - chassis.set_active_brake(0.1); + chassis.active_brake_set(0.1); } ``` @@ -213,18 +213,18 @@ void initialize() { --- -## toggle_modify_curve_with_controller() +## curve_toggle_modify_with_controller() Enables/disables buttons used for modifying the controller curve with the joystick. `toggle` true enables, false disables. **Prototype** ```cpp -void toggle_modify_curve_with_controller(bool toggle); +void curve_toggle_modify_with_controller(bool toggle); ``` **Example** ```cpp void initialize() { - chassis.toggle_modify_curve_with_controller(true); + chassis.curve_toggle_modify_with_controller(true); } ``` @@ -232,19 +232,19 @@ void initialize() { --- -## set_left_curve_buttons() +## curve_buttons_left_set() Sets the buttons that are used to modify the left input curve. The example is the default. `decrease` a pros button. `increase` a pros button. **Prototype** ```cpp -void set_left_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); +void curve_buttons_left_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); ``` **Example** ```cpp void initialize() { - chassis.set_left_curve_buttons (pros::E_CONTROLLER_DIGITAL_LEFT, pros::E_CONTROLLER_DIGITAL_RIGHT); + chassis.curve_buttons_left_set (pros::E_CONTROLLER_DIGITAL_LEFT, pros::E_CONTROLLER_DIGITAL_RIGHT); } ``` @@ -252,19 +252,19 @@ void initialize() { --- -## set_right_curve_buttons() +## curve_buttons_right_set() Sets the buttons that are used to modify the right input curve. The example is the default. `decrease` a pros button. `increase` a pros button. **Prototype** ```cpp -void set_right_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); +void curve_buttons_right_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); ``` **Example** ```cpp void initialize() { - chassis.set_right_curve_buttons(pros::E_CONTROLLER_DIGITAL_Y, pros::E_CONTROLLER_DIGITAL_A); + chassis.curve_buttons_right_set(pros::E_CONTROLLER_DIGITAL_Y, pros::E_CONTROLLER_DIGITAL_A); } ``` @@ -272,22 +272,22 @@ void initialize() { --- -## left_curve_function() +## curve_left_function() Returns the input times the red curve [here](https://www.desmos.com/calculator/rcfjjg83zx). `tank()`, `arcade_standard()`, and `arcade_flipped()` all handle this for you. When tank is enabled, only this curve is used. `x` input value. **Prototype** ```cpp -double left_curve_function(double x); +double curve_left_function(double x); ``` **Example** ```cpp void opcontrol() { while (true) { - int l_stick = left_curve_function(master.get_analog(ANALOG_LEFT_Y)); - int r_stick = left_curve_function(master.get_analog(ANALOG_RIGHT_Y)); + int l_stick = curve_left_function(master.get_analog(ANALOG_LEFT_Y)); + int r_stick = curve_left_function(master.get_analog(ANALOG_RIGHT_Y)); - chassis.set_tank(l_stick, r_stick); + chassis.tank_set(l_stick, r_stick); pros::delay(ez::util::DELAY_TIME); } @@ -298,22 +298,22 @@ void opcontrol() { --- -## right_curve_function() +## curve_right_function() Returns the input times the red curve [here](https://www.desmos.com/calculator/rcfjjg83zx). `tank()`, `arcade_standard()`, and `arcade_flipped()` all handle this for you. `x` input value. **Prototype** ```cpp -double right_curve_function(double x); +double curve_right_function(double x); ``` **Example** ```cpp void opcontrol() { while (true) { - int l_stick = left_curve_function(master.get_analog(ANALOG_LEFT_Y)); - int r_stick = left_curve_function(master.get_analog(ANALOG_RIGHT_Y)); + int l_stick = curve_left_function(master.get_analog(ANALOG_LEFT_Y)); + int r_stick = curve_left_function(master.get_analog(ANALOG_RIGHT_Y)); - chassis.set_tank(l_stick, r_stick); + chassis.tank_set(l_stick, r_stick); pros::delay(ez::util::DELAY_TIME); } @@ -324,18 +324,18 @@ void opcontrol() { --- -## set_joystick_threshold() +## joystick_threshold_set() Threshold the joystick will return 0 within. `threshold` an integer, recommended to be less then 5. **Prototype** ```cpp -void set_joystick_threshold(int threshold); +void joystick_threshold_set(int threshold); ``` **Example** ```cpp void initialize() { - chassis.set_joystick_threshold(5); + chassis.joystick_threshold_set(5); } ``` @@ -343,11 +343,11 @@ void initialize() { --- -## joy_thresh_opcontrol() +## joystick_threshold_opcontrol() Runs the joystick control. Sets the left drive to `l_stick`, and right drive to `r_stick`. Runs active brake and joystick thresholds. **Prototype** ```cpp -void joy_thresh_opcontrol(int l_stick, int r_stick); +void joystick_threshold_opcontrol(int l_stick, int r_stick); ``` **Example** @@ -358,17 +358,17 @@ void opcontrol() { pros::delay(ez::util::DELAY_TIME); } - chassis.set_joystick_threshold(5); + chassis.joystick_threshold_set(5); } ``` --- -## modify_curve_with_controller() +## curve_modify_with_controller() Allows the user to modify the curve with the controller. **Prototype** ```cpp -void modify_curve_with_controller(); +void curve_modify_with_controller(); ``` **Example** @@ -377,11 +377,11 @@ void opcontrol() { while (true) { chassis.joy_thresh_opcontroL(master.get_analog(ANALOG_LEFT_Y), master.get_analog(ANALOG_RIGHT_Y)); - chassis.modify_curve_with_controller(); + chassis.curve_modify_with_controller(); pros::delay(ez::util::DELAY_TIME); } - chassis.set_joystick_threshold(5); + chassis.joystick_threshold_set(5); } ``` diff --git a/docs/Docs/util.md b/docs/Docs/util.md index 9db256b1..89dfb3ab 100644 --- a/docs/Docs/util.md +++ b/docs/Docs/util.md @@ -30,10 +30,10 @@ extern pros::Controller master(); ```cpp void opcontrol() { while (true) { - int l_stick = left_curve_function(master.get_analog(ANALOG_LEFT_Y)); - int r_stick = left_curve_function(master.get_analog(ANALOG_RIGHT_Y)); + int l_stick = curve_left_function(master.get_analog(ANALOG_LEFT_Y)); + int r_stick = curve_left_function(master.get_analog(ANALOG_RIGHT_Y)); - chassis.set_tank(l_stick, r_stick); + chassis.tank_set(l_stick, r_stick); pros::delay(ez::util::DELAY_TIME); } diff --git a/docs/Releases/2.0.1.md b/docs/Releases/2.0.1.md index c9b42c25..920b6dcb 100644 --- a/docs/Releases/2.0.1.md +++ b/docs/Releases/2.0.1.md @@ -25,13 +25,13 @@ To upgrade your project, include a `&` in front of the PID. ```cpp void default_constants() { - chassis.set_slew_min_power(80, 80); - chassis.set_slew_distance(7, 7); + chassis.slew_min_power_set(80, 80); + chassis.slew_distance_set(7, 7); chassis.set_pid_constants(&chassis.headingPID, 11, 0, 20, 0); - chassis.set_pid_constants(&chassis.forward_drivePID, 0.45, 0, 5, 0); - chassis.set_pid_constants(&chassis.backward_drivePID, 0.45, 0, 5, 0); - chassis.set_pid_constants(&chassis.turnPID, 5, 0.003, 35, 15); - chassis.set_pid_constants(&chassis.swingPID, 7, 0, 45, 0); + chassis.set_pid_constants(&chassis.pid_forward_drive, 0.45, 0, 5, 0); + chassis.set_pid_constants(&chassis.pid_backward_drive, 0.45, 0, 5, 0); + chassis.set_pid_constants(&chassis.pid_turn, 5, 0.003, 35, 15); + chassis.set_pid_constants(&chassis.pid_swing, 7, 0, 45, 0); } ``` diff --git a/docs/Releases/2.1.0.md b/docs/Releases/2.1.0.md index 68fa4612..0466ab2a 100644 --- a/docs/Releases/2.1.0.md +++ b/docs/Releases/2.1.0.md @@ -25,10 +25,10 @@ Please put `chassis.reset_pid_constants();` at the start of your `void autonomou ```cpp void autonomous() { - chassis.reset_pid_targets(); // Resets PID targets to 0 - chassis.reset_gyro(); // Reset gyro position to 0 - chassis.reset_drive_sensor(); // Reset drive sensors to 0 - chassis.set_drive_brake(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. + chassis.pid_targets_reset(); // Resets PID targets to 0 + chassis.imu_reset(); // Reset gyro position to 0 + chassis.drive_sensors_reset(); // Reset drive sensors to 0 + chassis.drive_brake_set(MOTOR_BRAKE_HOLD); // Set motors to hold. This helps autonomous consistency. ez::as::auton_selector.selected_auton_call(); // Calls selected auton from autonomous selector. } diff --git a/docs/Tutorials/activebrake.md b/docs/Tutorials/activebrake.md index 840d03fc..b5273559 100644 --- a/docs/Tutorials/activebrake.md +++ b/docs/Tutorials/activebrake.md @@ -22,7 +22,7 @@ nav_order: 6 If you put the motors on brake type hold, a robot can still push the robot a bit, and when you let go of the joysticks the robot just locks in place. Active brake runs a P loop on the drive when you let go of the joysticks. By adjusting the kP, you adjust how hard the robot fights back. If you make it smaller, there will be a larger dead zone and you'll coast a little bit. Active brake vs brake type is personal preference. ## Enabling -To adjust the kP, in `src/main.cpp` change `chassis.set_active_brake(0)` to whatever you like! We suggest around `0.1`. +To adjust the kP, in `src/main.cpp` change `chassis.active_brake_set(0)` to whatever you like! We suggest around `0.1`. ## Disabling -To disable active brake, in `src/main.cpp` make sure the kP is 0 with `chassis.set_active_brake(0)`. \ No newline at end of file +To disable active brake, in `src/main.cpp` make sure the kP is 0 with `chassis.active_brake_set(0)`. \ No newline at end of file diff --git a/docs/Tutorials/example_autons.md b/docs/Tutorials/example_autons.md index 99d13380..9b80e941 100644 --- a/docs/Tutorials/example_autons.md +++ b/docs/Tutorials/example_autons.md @@ -20,7 +20,7 @@ nav_order: 2 -## Assumed Constants +## Assumed constants_ ```cpp const int DRIVE_SPEED = 110; const int TURN_SPEED = 90; @@ -40,14 +40,14 @@ void drive_example() { // for slew, only enable it when the drive distance is greater then the slew distance + a few inches - chassis.set_drive_pid(24, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(24, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-12, DRIVE_SPEED); - chassis.wait_drive(); + chassis.pid_drive_set(-12, DRIVE_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-12, DRIVE_SPEED); - chassis.wait_drive(); + chassis.pid_drive_set(-12, DRIVE_SPEED); + chassis.drive_wait_exit(); } ``` @@ -62,14 +62,14 @@ void turn_example() { // The second parameter is max speed the robot will drive at - chassis.set_turn_pid(90, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(90, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); } ``` @@ -80,20 +80,20 @@ void turn_example() { ## Drive and Turn ```cpp void drive_and_turn() { - chassis.set_drive_pid(24, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(24, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(-45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(-45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-24, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(-24, DRIVE_SPEED, true); + chassis.drive_wait_exit(); } ``` @@ -104,29 +104,29 @@ void drive_and_turn() { ## Wait Until and Changing Speed ```cpp void wait_until_change_speed() { - // wait_until will wait until the robot gets to a desired position + // drive_wait_distance will wait until the robot gets to a desired position // When the robot gets to 6 inches, the robot will travel the remaining distance at a max speed of 40 - chassis.set_drive_pid(24, DRIVE_SPEED, true); - chassis.wait_until(6); - chassis.set_max_speed(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed - chassis.wait_drive(); + chassis.pid_drive_set(24, DRIVE_SPEED, true); + chassis.drive_wait_distance(6); + chassis.max_speed_set(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(-45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(-45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); // When the robot gets to -6 inches, the robot will travel the remaining distance at a max speed of 40 - chassis.set_drive_pid(-24, DRIVE_SPEED, true); - chassis.wait_until(-6); - chassis.set_max_speed(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed - chassis.wait_drive(); + chassis.pid_drive_set(-24, DRIVE_SPEED, true); + chassis.drive_wait_distance(-6); + chassis.max_speed_set(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed + chassis.drive_wait_exit(); } ``` @@ -142,14 +142,14 @@ void swing_example() { // The third parameter is speed of the moving side of the drive - chassis.set_swing_pid(ez::LEFT_SWING, 45, SWING_SPEED); - chassis.wait_drive(); + chassis.pid_swing_set(ez::LEFT_SWING, 45, SWING_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(24, DRIVE_SPEED, true); - chassis.wait_until(12); + chassis.pid_drive_set(24, DRIVE_SPEED, true); + chassis.drive_wait_distance(12); - chassis.set_swing_pid(ez::RIGHT_SWING, 0, SWING_SPEED); - chassis.wait_drive(); + chassis.pid_swing_set(ez::RIGHT_SWING, 0, SWING_SPEED); + chassis.drive_wait_exit(); } ``` @@ -160,20 +160,20 @@ void swing_example() { ## Combining All Movements ```cpp void combining_movements() { - chassis.set_drive_pid(24, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(24, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(ez::RIGHT_SWING, -45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_drive_set(ez::RIGHT_SWING, -45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-24, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(-24, DRIVE_SPEED, true); + chassis.drive_wait_exit(); } ``` @@ -187,13 +187,13 @@ void tug (int attempts) { for (int i=0; i left_motors; + std::vector motors_left; /** * Vector of pros motors for the right chassis. */ - std::vector right_motors; + std::vector motors_right; /** * Vector of pros motors that are disconnected from the drive. @@ -62,33 +62,33 @@ class Drive { /** * Left tracking wheel. */ - pros::ADIEncoder left_tracker; + pros::ADIEncoder tracker_left; /** * Right tracking wheel. */ - pros::ADIEncoder right_tracker; + pros::ADIEncoder tracker_right; /** * Left rotation tracker. */ - pros::Rotation left_rotation; + pros::Rotation rotation_left; /** * Right rotation tracker. */ - pros::Rotation right_rotation; + pros::Rotation rotation_right; /** * PID objects. */ - PID headingPID; - PID turnPID; - PID forward_drivePID; - PID leftPID; - PID rightPID; - PID backward_drivePID; - PID swingPID; + PID pid_heading; + PID pid_turn; + PID pid_forward_drive; + PID pid_left; + PID pid_right; + PID pid_backward_drive; + PID pid_swing; /** * Current mode of the drive. @@ -98,12 +98,12 @@ class Drive { /** * Sets current mode of drive. */ - void set_mode(e_mode p_mode); + void mode_set(e_mode p_mode); /** * Returns current mode of drive. */ - e_mode get_mode(); + e_mode mode_get(); /** * Calibrates imu and initializes sd card to curve. @@ -202,7 +202,7 @@ class Drive { /** * Sets drive defaults. */ - void set_defaults(); + void defaults_set(); ///// // @@ -237,7 +237,7 @@ class Drive { /** * Initializes left and right curves with the SD card, recommended to run in initialize(). */ - void init_curve_sd(); + void curve_init_sd(); /** * Sets the default joystick curves. @@ -247,7 +247,7 @@ class Drive { * \param right * Right default curve. */ - void set_curve_default(double left, double right = 0); + void curve_set_default(double left, double right = 0); /** * Runs a P loop on the drive when the joysticks are released. @@ -255,7 +255,7 @@ class Drive { * \param kp * Constant for the p loop. */ - void set_active_brake(double kp); + void active_brake_set(double kp); /** * Enables/disables modifying the joystick input curves with the controller. True enables, false disables. @@ -263,7 +263,7 @@ class Drive { * \param input * bool input */ - void toggle_modify_curve_with_controller(bool toggle); + void curve_toggle_modify_with_controller(bool toggle); /** * Sets buttons for modifying the left joystick curve. @@ -273,7 +273,7 @@ class Drive { * \param increase * a pros button enumerator */ - void set_left_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); + void curve_buttons_left_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); /** * Sets buttons for modifying the right joystick curve. @@ -283,7 +283,7 @@ class Drive { * \param increase * a pros button enumerator */ - void set_right_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); + void curve_buttons_right_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase); /** * Outputs a curve from 5225A In the Zone. This gives more control over the robot at lower speeds. https://www.desmos.com/calculator/rcfjjg83zx @@ -291,7 +291,7 @@ class Drive { * \param x * joystick input */ - double left_curve_function(double x); + double curve_left_function(double x); /** * Outputs a curve from 5225A In the Zone. This gives more control over the robot at lower speeds. https://www.desmos.com/calculator/rcfjjg83zx @@ -299,7 +299,7 @@ class Drive { * \param x * joystick input */ - double right_curve_function(double x); + double curve_right_function(double x); /** * Sets a new threshold for the joystick. The joysticks wil not return a value if they are within this. @@ -307,12 +307,12 @@ class Drive { * \param threshold * new threshold */ - void set_joystick_threshold(int threshold); + void joystick_threshold_set(int threshold); /** * Resets drive sensors at the start of opcontrol. */ - void reset_drive_sensors_opcontrol(); + void drive_sensors_reset_opcontrol(); /** * Sets minimum slew distance constants. @@ -322,7 +322,7 @@ class Drive { * \param r_stick * input for right joystick */ - void joy_thresh_opcontrol(int l_stick, int r_stick); + void joystick_threshold_opcontrol(int l_stick, int r_stick); ///// // @@ -378,7 +378,7 @@ class Drive { * \param right * voltage for right side, -127 to 127 */ - void set_tank(int left, int right); + void tank_set(int left, int right); /** * Changes the way the drive behaves when it is not under active user control @@ -386,7 +386,7 @@ class Drive { * \param brake_type * the 'brake mode' of the motor e.g. 'pros::E_MOTOR_BRAKE_COAST' 'pros::E_MOTOR_BRAKE_BRAKE' 'pros::E_MOTOR_BRAKE_HOLD' */ - void set_drive_brake(pros::motor_brake_mode_e_t brake_type); + void drive_brake_set(pros::motor_brake_mode_e_t brake_type); /** * Sets the limit for the current on the drive. @@ -394,17 +394,17 @@ class Drive { * \param mA * input in milliamps */ - void set_drive_current_limit(int mA); + void drive_current_limit_set(int mA); /** * Toggles set drive in autonomous. True enables, false disables. */ - void toggle_auto_drive(bool toggle); + void auto_drive_toggle(bool toggle); /** * Toggles printing in autonomous. True enables, false disables. */ - void toggle_auto_print(bool toggle); + void auto_print_toggle(bool toggle); ///// // @@ -415,57 +415,57 @@ class Drive { /** * The position of the right motor. */ - double right_sensor(); + double sensor_right(); /** * The position of the right motor. */ - int raw_right_sensor(); + int sensor_right_raw(); /** * The velocity of the right motor. */ - int right_velocity(); + int velocity_right(); /** * The watts of the right motor. */ - double right_mA(); + double mA_right(); /** * Return TRUE when the motor is over current. */ - bool right_over_current(); + bool over_current_right(); /** * The position of the left motor. */ - double left_sensor(); + double sensor_left(); /** * The position of the left motor. */ - int raw_left_sensor(); + int sensor_left_raw(); /** * The velocity of the left motor. */ - int left_velocity(); + int velocity_left(); /** * The watts of the left motor. */ - double left_mA(); + double mA_left(); /** * Return TRUE when the motor is over current. */ - bool left_over_current(); + bool over_current_left(); /** * Reset all the chassis motors, recommended to run at the start of your autonomous routine. */ - void reset_drive_sensor(); + void drive_sensors_reset(); /** * Resets the current gyro value. Defaults to 0, recommended to run at the start of your autonomous routine. @@ -473,12 +473,12 @@ class Drive { * \param new_heading * New heading value. */ - void reset_gyro(double new_heading = 0); + void imu_reset(double new_heading = 0); /** * Returns the current gyro value. */ - double get_gyro(); + double imu_get(); /** * Calibrates the IMU, recommended to run in initialize(). @@ -498,7 +498,7 @@ class Drive { * * @param toggle True if you want this mode enables and False if you want it disabled. */ - void toggle_practice_mode(bool toggle); + void practice_mode_toggle(bool toggle); ///// // @@ -518,7 +518,7 @@ class Drive { * \param toggle_heading * toggle for heading correction */ - void set_drive_pid(okapi::QLength p_target, int speed, bool slew_on = false, bool toggle_heading = true); + void pid_drive_set(okapi::QLength p_target, int speed, bool slew_on = false, bool toggle_heading = true); /** * Sets the robot to turn using PID. @@ -528,17 +528,17 @@ class Drive { * \param speed * 0 to 127, max speed during motion */ - void set_turn_pid(double target, int speed); + void pid_turn_set(double target, int speed); /** - * Sets the robot to turn relative to current heading using PID. - * - * \param target - * target in degrees relative to current heading - * \param speed - * 0 to 127, max speed during motion - */ - void set_relative_turn_pid(double target, int speed); + * Sets the robot to turn relative to current heading using PID. + * + * \param target + * target in degrees relative to current heading + * \param speed + * 0 to 127, max speed during motion + */ + void pid_relative_turn_set(double target, int speed); /** * Turn using only the left or right side. @@ -550,22 +550,22 @@ class Drive { * \param speed * 0 to 127, max speed during motion */ - void set_swing_pid(e_swing type, double target, int speed); + void pid_swing_set(e_swing type, double target, int speed); /** * Resets all PID targets to 0. */ - void reset_pid_targets(); + void pid_targets_reset(); /** * Sets heading of gyro and target of PID. */ - void set_angle(double angle); + void angle_set(double angle); /** * Lock the code in a while loop until the robot has settled. */ - void wait_drive(); + void drive_wait_exit(); /** * Lock the code in a while loop until this position has passed. @@ -573,7 +573,7 @@ class Drive { * \param target * when driving, this is inches. when turning, this is degrees. */ - void wait_until(double target); + void drive_wait_distance(double target); /** * Lock the code in a while loop until this position has passed for driving with okapi units. @@ -581,7 +581,7 @@ class Drive { * \param target * for driving, using okapi units */ - void wait_until(okapi::QLength target); + void drive_wait_distance(okapi::QLength target); /** * Autonomous interference detection. Returns true when interfered, and false when nothing happened. @@ -594,14 +594,14 @@ class Drive { * @param ratio * ratio of the gears */ - void set_ratio(double ratio); + void ratio_set(double ratio); /** * Changes max speed during a drive motion. * * \param speed * new clipped speed */ - void set_max_speed(int speed); + void max_speed_set(int speed); /** * @brief Set the drive pid constants object @@ -611,7 +611,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_drive_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_drive_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * @brief Set the turn pid constants object @@ -621,7 +621,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_turn_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_turn_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * @brief Set the swing pid constants object @@ -631,7 +631,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_swing_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_swing_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * @brief Set the heading pid constants object @@ -641,7 +641,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_heading_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_heading_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * @brief Set the forward pid constants object @@ -651,7 +651,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_drive_forward_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_drive_forward_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * @brief Set the backwards pid constants object @@ -661,7 +661,7 @@ class Drive { * @param d kD * @param p_start_i start_I */ - void set_drive_backwards_pid_constants(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); + void pid_drive_backwards_constants_set(double p, double i = 0.0, double d = 0.0, double p_start_i = 0.0); /** * Sets minimum power for swings when kI and startI are enabled. @@ -669,7 +669,7 @@ class Drive { * \param min * new clipped speed */ - void set_swing_min(int min); + void swing_min_set(int min); /** * The minimum power for turns when kI and startI are enabled. @@ -677,17 +677,17 @@ class Drive { * \param min * new clipped speed */ - void set_turn_min(int min); + void turn_min_set(int min); /** * Returns minimum power for swings when kI and startI are enabled. */ - int get_swing_min(); + int swing_min_get(); /** * Returns minimum power for turns when kI and startI are enabled. */ - int get_turn_min(); + int turn_min_get(); /** * Sets minimum slew speed constants. @@ -697,7 +697,7 @@ class Drive { * \param rev * minimum power for backwards drive pd */ - void set_slew_min_power(int fwd, int rev); + void slew_min_power_set(int fwd, int rev); /** * Sets minimum slew distance constants. @@ -707,7 +707,7 @@ class Drive { * \param rev * minimum distance for backwards drive pd, okapi unit */ - void set_slew_distance(okapi::QLength fwd, okapi::QLength rev); + void slew_distance_set(okapi::QLength fwd, okapi::QLength rev); /** * Set's constants for drive exit conditions. @@ -723,7 +723,7 @@ class Drive { * \param p_velocity_exit_time * Sets velocity_exit_time. Timer will start when velocity is 0. */ - void set_drive_exit_condition(int p_small_exit_time, okapi::QLength p_small_error, int p_big_exit_time, okapi::QLength p_big_error, int p_velocity_exit_time, int p_mA_timeout); + void drive_exit_condition_set(int p_small_exit_time, okapi::QLength p_small_error, int p_big_exit_time, okapi::QLength p_big_error, int p_velocity_exit_time, int p_mA_timeout); /** * Set's constants for turn exit conditions. @@ -739,7 +739,7 @@ class Drive { * \param p_velocity_exit_time * Sets velocity_exit_time. Timer will start when velocity is 0. */ - void set_turn_exit_condition(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout); + void turn_exit_condition_set(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout); /** * Set's constants for swing exit conditions. @@ -755,17 +755,17 @@ class Drive { * \param p_velocity_exit_time * Sets velocity_exit_time. Timer will start when velocity is 0. */ - void set_swing_exit_condition(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout); + void swing_exit_condition_set(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout); /** * Returns current tick_per_inch() */ - double get_tick_per_inch(); + double tick_per_inch_get(); /** * Returns current tick_per_inch() */ - void modify_curve_with_controller(); + void curve_modify_with_controller(); // Slew struct slew_ { @@ -776,11 +776,11 @@ class Drive { double slope = 0; double output = 0; bool enabled = false; - double max_speed = 0; + double speed_max = 0; }; - slew_ left_slew; - slew_ right_slew; + slew_ slew_left; + slew_ slew_right; /** * Initialize slew. @@ -789,7 +789,7 @@ class Drive { * slew_ enum * \param slew_on * is slew on? - * \param max_speed + * \param speed_max * target speed during the slew * \param target * target sensor value @@ -800,7 +800,7 @@ class Drive { * \param backwards * slew direction for constants */ - void slew_initialize(slew_ &input, bool slew_on, double max_speed, double target, double current, double start, bool backwards); + void slew_initialize(slew_ &input, bool slew_on, double speed_max, double target, double current, double start, bool backwards); /** * Calculate slew. @@ -822,7 +822,7 @@ class Drive { /** * Private wait until for drive */ - void wait_until_drive(double target); + void drive_wait_until(double target); /** * Sets the chassis to voltage. @@ -832,12 +832,12 @@ class Drive { * \param right * voltage for right side, -127 to 127 */ - void private_set_tank(int left, int right); + void tank_set_private(int left, int right); /** * Returns joystick value clipped to JOYSTICK_THRESH */ - int clipped_joystick(int joystick); + int joystick_clamped(int joystick); /** * Heading bool. @@ -863,14 +863,14 @@ class Drive { /** * Max speed for autonomous. */ - int max_speed; + int speed_max; /** * Tasks */ - void drive_pid_task(); - void swing_pid_task(); - void turn_pid_task(); + void pid_drive_task(); + void pid_swing_task(); + void pid_turn_task(); void ez_auto_task(); /** @@ -882,18 +882,18 @@ class Drive { /** * Starting value for left/right */ - double l_start = 0; - double r_start = 0; + double start_left = 0; + double start_right = 0; /** * Enable/disable modifying controller curve with controller. */ - bool disable_controller = true; // True enables, false disables. + bool controller_disable = true; // True enables, false disables. /** * Is tank drive running? */ - bool is_tank; + bool tank_active; #define DRIVE_INTEGRATED 1 #define DRIVE_ADI_ENCODER 2 @@ -902,13 +902,13 @@ class Drive { /** * Is tracking? */ - int is_tracker = DRIVE_INTEGRATED; + int tracker_active = DRIVE_INTEGRATED; /** * Save input to sd card */ - void save_l_curve_sd(); - void save_r_curve_sd(); + void curve_left_save_sd(); + void curve_right_save_sd(); /** * Struct for buttons for increasing/decreasing curve with controller @@ -922,10 +922,10 @@ class Drive { pros::controller_digital_e_t button; }; - button_ l_increase_; - button_ l_decrease_; - button_ r_increase_; - button_ r_decrease_; + button_ left_increase_; + button_ left_decrease_; + button_ right_increase_; + button_ right_decrease_; /** * Function for button presses. @@ -935,14 +935,14 @@ class Drive { /** * The left and right curve scalers. */ - double left_curve_scale; - double right_curve_scale; + double curve_left_scale; + double curve_right_scale; /** * Increase and decrease left and right curve scale. */ - void l_decrease(); - void l_increase(); - void r_decrease(); - void r_increase(); + void curve_left_scale_decrease(); + void curve_left_scale_increase(); + void curve_right_scale_decrease(); + void curve_right_scale_increase(); }; diff --git a/src/EZ-Template/drive/drive.cpp b/src/EZ-Template/drive/drive.cpp index 79c99685..a09866c1 100644 --- a/src/EZ-Template/drive/drive.cpp +++ b/src/EZ-Template/drive/drive.cpp @@ -18,30 +18,30 @@ using namespace ez; Drive::Drive(std::vector left_motor_ports, std::vector right_motor_ports, int imu_port, double wheel_diameter, double ticks, double ratio) : imu(imu_port), - left_tracker(-1, -1, false), // Default value - right_tracker(-1, -1, false), // Default value - left_rotation(-1), - right_rotation(-1), + tracker_left(-1, -1, false), // Default value + tracker_right(-1, -1, false), // Default value + rotation_left(-1), + rotation_right(-1), ez_auto([this] { this->ez_auto_task(); }) { - is_tracker = DRIVE_INTEGRATED; + tracker_active = DRIVE_INTEGRATED; // Set ports to a global vector for (auto i : left_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - left_motors.push_back(temp); + motors_left.push_back(temp); } for (auto i : right_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - right_motors.push_back(temp); + motors_right.push_back(temp); } // Set constants for tick_per_inch calculation WHEEL_DIAMETER = wheel_diameter; RATIO = ratio; CARTRIDGE = ticks; - TICK_PER_INCH = get_tick_per_inch(); + TICK_PER_INCH = tick_per_inch_get(); - set_defaults(); + defaults_set(); } // Constructor for tracking wheels plugged into the brain @@ -49,30 +49,30 @@ Drive::Drive(std::vector left_motor_ports, std::vector right_motor_por int imu_port, double wheel_diameter, double ticks, double ratio, std::vector left_tracker_ports, std::vector right_tracker_ports) : imu(imu_port), - left_tracker(abs(left_tracker_ports[0]), abs(left_tracker_ports[1]), util::reversed_active(left_tracker_ports[0])), - right_tracker(abs(right_tracker_ports[0]), abs(right_tracker_ports[1]), util::reversed_active(right_tracker_ports[0])), - left_rotation(-1), - right_rotation(-1), + tracker_left(abs(left_tracker_ports[0]), abs(left_tracker_ports[1]), util::reversed_active(left_tracker_ports[0])), + tracker_right(abs(right_tracker_ports[0]), abs(right_tracker_ports[1]), util::reversed_active(right_tracker_ports[0])), + rotation_left(-1), + rotation_right(-1), ez_auto([this] { this->ez_auto_task(); }) { - is_tracker = DRIVE_ADI_ENCODER; + tracker_active = DRIVE_ADI_ENCODER; // Set ports to a global vector for (auto i : left_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - left_motors.push_back(temp); + motors_left.push_back(temp); } for (auto i : right_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - right_motors.push_back(temp); + motors_right.push_back(temp); } // Set constants for tick_per_inch calculation WHEEL_DIAMETER = wheel_diameter; RATIO = ratio; CARTRIDGE = ticks; - TICK_PER_INCH = get_tick_per_inch(); + TICK_PER_INCH = tick_per_inch_get(); - set_defaults(); + defaults_set(); } // Constructor for tracking wheels plugged into a 3 wire expander @@ -80,30 +80,30 @@ Drive::Drive(std::vector left_motor_ports, std::vector right_motor_por int imu_port, double wheel_diameter, double ticks, double ratio, std::vector left_tracker_ports, std::vector right_tracker_ports, int expander_smart_port) : imu(imu_port), - left_tracker({expander_smart_port, abs(left_tracker_ports[0]), abs(left_tracker_ports[1])}, util::reversed_active(left_tracker_ports[0])), - right_tracker({expander_smart_port, abs(right_tracker_ports[0]), abs(right_tracker_ports[1])}, util::reversed_active(right_tracker_ports[0])), - left_rotation(-1), - right_rotation(-1), + tracker_left({expander_smart_port, abs(left_tracker_ports[0]), abs(left_tracker_ports[1])}, util::reversed_active(left_tracker_ports[0])), + tracker_right({expander_smart_port, abs(right_tracker_ports[0]), abs(right_tracker_ports[1])}, util::reversed_active(right_tracker_ports[0])), + rotation_left(-1), + rotation_right(-1), ez_auto([this] { this->ez_auto_task(); }) { - is_tracker = DRIVE_ADI_ENCODER; + tracker_active = DRIVE_ADI_ENCODER; // Set ports to a global vector for (auto i : left_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - left_motors.push_back(temp); + motors_left.push_back(temp); } for (auto i : right_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - right_motors.push_back(temp); + motors_right.push_back(temp); } // Set constants for tick_per_inch calculation WHEEL_DIAMETER = wheel_diameter; RATIO = ratio; CARTRIDGE = ticks; - TICK_PER_INCH = get_tick_per_inch(); + TICK_PER_INCH = tick_per_inch_get(); - set_defaults(); + defaults_set(); } // Constructor for rotation sensors @@ -111,71 +111,71 @@ Drive::Drive(std::vector left_motor_ports, std::vector right_motor_por int imu_port, double wheel_diameter, double ratio, int left_rotation_port, int right_rotation_port) : imu(imu_port), - left_tracker(-1, -1, false), // Default value - right_tracker(-1, -1, false), // Default value - left_rotation(abs(left_rotation_port)), - right_rotation(abs(right_rotation_port)), + tracker_left(-1, -1, false), // Default value + tracker_right(-1, -1, false), // Default value + rotation_left(abs(left_rotation_port)), + rotation_right(abs(right_rotation_port)), ez_auto([this] { this->ez_auto_task(); }) { - is_tracker = DRIVE_ROTATION; - left_rotation.set_reversed(util::reversed_active(left_rotation_port)); - right_rotation.set_reversed(util::reversed_active(right_rotation_port)); + tracker_active = DRIVE_ROTATION; + rotation_left.set_reversed(util::reversed_active(left_rotation_port)); + rotation_right.set_reversed(util::reversed_active(right_rotation_port)); // Set ports to a global vector for (auto i : left_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - left_motors.push_back(temp); + motors_left.push_back(temp); } for (auto i : right_motor_ports) { pros::Motor temp(abs(i), util::reversed_active(i)); - right_motors.push_back(temp); + motors_right.push_back(temp); } // Set constants for tick_per_inch calculation WHEEL_DIAMETER = wheel_diameter; RATIO = ratio; CARTRIDGE = 36000; - TICK_PER_INCH = get_tick_per_inch(); + TICK_PER_INCH = tick_per_inch_get(); - set_defaults(); + defaults_set(); } -void Drive::set_defaults() { +void Drive::defaults_set() { // PID Constants - set_heading_pid_constants(3, 0, 20, 0); - set_drive_pid_constants(15, 0, 150); - set_turn_pid_constants(3, 0, 20, 0); - set_swing_pid_constants(5, 0, 30, 0); - set_turn_min(30); - set_swing_min(30); + pid_heading_constants_set(3, 0, 20, 0); + pid_drive_constants_set(15, 0, 150); + pid_turn_constants_set(3, 0, 20, 0); + pid_swing_constants_set(5, 0, 30, 0); + turn_min_set(30); + swing_min_set(30); // Slew constants - set_slew_min_power(80, 80); - set_slew_distance(7_in, 7_in); + slew_min_power_set(80, 80); + slew_distance_set(7_in, 7_in); // Exit condition constants - set_turn_exit_condition(200, 3, 500, 7, 750, 750); - set_swing_exit_condition(200, 3, 500, 7, 750, 750); - set_drive_exit_condition(200, 1_in, 500, 3_in, 750, 750); + turn_exit_condition_set(200, 3, 500, 7, 750, 750); + swing_exit_condition_set(200, 3, 500, 7, 750, 750); + drive_exit_condition_set(200, 1_in, 500, 3_in, 750, 750); // Modify joystick curve on controller (defaults to disabled) - toggle_modify_curve_with_controller(true); + curve_toggle_modify_with_controller(true); // Left / Right modify buttons - set_left_curve_buttons(pros::E_CONTROLLER_DIGITAL_LEFT, pros::E_CONTROLLER_DIGITAL_RIGHT); - set_right_curve_buttons(pros::E_CONTROLLER_DIGITAL_Y, pros::E_CONTROLLER_DIGITAL_A); + curve_buttons_left_set(pros::E_CONTROLLER_DIGITAL_LEFT, pros::E_CONTROLLER_DIGITAL_RIGHT); + curve_buttons_right_set(pros::E_CONTROLLER_DIGITAL_Y, pros::E_CONTROLLER_DIGITAL_A); // Enable auto printing and drive motors moving - toggle_auto_drive(true); - toggle_auto_print(true); + auto_drive_toggle(true); + auto_print_toggle(true); // Disables limit switch for auto selector as::limit_switch_lcd_initialize(nullptr, nullptr); } -double Drive::get_tick_per_inch() { +double Drive::tick_per_inch_get() { CIRCUMFERENCE = WHEEL_DIAMETER * M_PI; - if (is_tracker == DRIVE_ADI_ENCODER || is_tracker == DRIVE_ROTATION) + if (tracker_active == DRIVE_ADI_ENCODER || tracker_active == DRIVE_ROTATION) TICK_PER_REV = CARTRIDGE * RATIO; else TICK_PER_REV = (50.0 * (3600.0 / CARTRIDGE)) * RATIO; // with no cart, the encoder reads 50 counts per rotation @@ -184,78 +184,78 @@ double Drive::get_tick_per_inch() { return TICK_PER_INCH; } -void Drive::set_ratio(double ratio) { RATIO = ratio; } +void Drive::ratio_set(double ratio) { RATIO = ratio; } -void Drive::private_set_tank(int left, int right) { +void Drive::tank_set_private(int left, int right) { if (pros::millis() < 1500) return; - for (auto i : left_motors) { + for (auto i : motors_left) { if (!pto_check(i)) i.move_voltage(left * (12000.0 / 127.0)); // If the motor is in the pto list, don't do anything to the motor. } - for (auto i : right_motors) { + for (auto i : motors_right) { if (!pto_check(i)) i.move_voltage(right * (12000.0 / 127.0)); // If the motor is in the pto list, don't do anything to the motor. } } -void Drive::set_tank(int left, int right) { - set_mode(DISABLE); - private_set_tank(left, right); +void Drive::tank_set(int left, int right) { + mode_set(DISABLE); + tank_set_private(left, right); } -void Drive::set_drive_current_limit(int mA) { +void Drive::drive_current_limit_set(int mA) { if (abs(mA) > 2500) { mA = 2500; } CURRENT_MA = mA; - for (auto i : left_motors) { + for (auto i : motors_left) { if (!pto_check(i)) i.set_current_limit(abs(mA)); // If the motor is in the pto list, don't do anything to the motor. } - for (auto i : right_motors) { + for (auto i : motors_right) { if (!pto_check(i)) i.set_current_limit(abs(mA)); // If the motor is in the pto list, don't do anything to the motor. } } // Motor telemetry -void Drive::reset_drive_sensor() { - left_motors.front().tare_position(); - right_motors.front().tare_position(); - if (is_tracker == DRIVE_ADI_ENCODER) { - left_tracker.reset(); - right_tracker.reset(); +void Drive::drive_sensors_reset() { + motors_left.front().tare_position(); + motors_right.front().tare_position(); + if (tracker_active == DRIVE_ADI_ENCODER) { + tracker_left.reset(); + tracker_right.reset(); return; - } else if (is_tracker == DRIVE_ROTATION) { - left_rotation.reset_position(); - right_rotation.reset_position(); + } else if (tracker_active == DRIVE_ROTATION) { + rotation_left.reset_position(); + rotation_right.reset_position(); return; } } -int Drive::raw_right_sensor() { - if (is_tracker == DRIVE_ADI_ENCODER) - return right_tracker.get_value(); - else if (is_tracker == DRIVE_ROTATION) - return right_rotation.get_position(); - return right_motors.front().get_position(); +int Drive::sensor_right_raw() { + if (tracker_active == DRIVE_ADI_ENCODER) + return tracker_right.get_value(); + else if (tracker_active == DRIVE_ROTATION) + return rotation_right.get_position(); + return motors_right.front().get_position(); } -double Drive::right_sensor() { return raw_right_sensor() / get_tick_per_inch(); } -int Drive::right_velocity() { return right_motors.front().get_actual_velocity(); } -double Drive::right_mA() { return right_motors.front().get_current_draw(); } -bool Drive::right_over_current() { return right_motors.front().is_over_current(); } - -int Drive::raw_left_sensor() { - if (is_tracker == DRIVE_ADI_ENCODER) - return left_tracker.get_value(); - else if (is_tracker == DRIVE_ROTATION) - return left_rotation.get_position(); - return left_motors.front().get_position(); +double Drive::sensor_right() { return sensor_right_raw() / tick_per_inch_get(); } +int Drive::velocity_right() { return motors_right.front().get_actual_velocity(); } +double Drive::mA_right() { return motors_right.front().get_current_draw(); } +bool Drive::over_current_right() { return motors_right.front().is_over_current(); } + +int Drive::sensor_left_raw() { + if (tracker_active == DRIVE_ADI_ENCODER) + return tracker_left.get_value(); + else if (tracker_active == DRIVE_ROTATION) + return rotation_left.get_position(); + return motors_left.front().get_position(); } -double Drive::left_sensor() { return raw_left_sensor() / get_tick_per_inch(); } -int Drive::left_velocity() { return left_motors.front().get_actual_velocity(); } -double Drive::left_mA() { return left_motors.front().get_current_draw(); } -bool Drive::left_over_current() { return left_motors.front().is_over_current(); } +double Drive::sensor_left() { return sensor_left_raw() / tick_per_inch_get(); } +int Drive::velocity_left() { return motors_left.front().get_actual_velocity(); } +double Drive::mA_left() { return motors_left.front().get_current_draw(); } +bool Drive::over_current_left() { return motors_left.front().is_over_current(); } -void Drive::reset_gyro(double new_heading) { imu.set_rotation(new_heading); } -double Drive::get_gyro() { return imu.get_rotation(); } +void Drive::imu_reset(double new_heading) { imu.set_rotation(new_heading); } +double Drive::imu_get() { return imu.get_rotation(); } void Drive::imu_loading_display(int iter) { // If the lcd is already initialized, don't run this function @@ -313,21 +313,21 @@ bool Drive::imu_calibrate(bool run_loading_animation) { } // Brake modes -void Drive::set_drive_brake(pros::motor_brake_mode_e_t brake_type) { +void Drive::drive_brake_set(pros::motor_brake_mode_e_t brake_type) { CURRENT_BRAKE = brake_type; - for (auto i : left_motors) { + for (auto i : motors_left) { if (!pto_check(i)) i.set_brake_mode(brake_type); // If the motor is in the pto list, don't do anything to the motor. } - for (auto i : right_motors) { + for (auto i : motors_right) { if (!pto_check(i)) i.set_brake_mode(brake_type); // If the motor is in the pto list, don't do anything to the motor. } } void Drive::initialize() { - init_curve_sd(); + curve_init_sd(); imu_calibrate(); - reset_drive_sensor(); + drive_sensors_reset(); } -void Drive::toggle_auto_drive(bool toggle) { drive_toggle = toggle; } -void Drive::toggle_auto_print(bool toggle) { print_toggle = toggle; } \ No newline at end of file +void Drive::auto_drive_toggle(bool toggle) { drive_toggle = toggle; } +void Drive::auto_print_toggle(bool toggle) { print_toggle = toggle; } \ No newline at end of file diff --git a/src/EZ-Template/drive/exit_conditions.cpp b/src/EZ-Template/drive/exit_conditions.cpp index 808aa78c..8b989dae 100644 --- a/src/EZ-Template/drive/exit_conditions.cpp +++ b/src/EZ-Template/drive/exit_conditions.cpp @@ -9,20 +9,20 @@ file, You can obtain one at http://mozilla.org/MPL/2.0/. using namespace ez; -void Drive::set_drive_exit_condition(int p_small_exit_time, okapi::QLength p_small_error, int p_big_exit_time, okapi::QLength p_big_error, int p_velocity_exit_time, int p_mA_timeout) { - leftPID.exit_condition_set(p_small_exit_time, p_small_error.convert(okapi::inch), p_big_exit_time, p_big_error.convert(okapi::inch), p_velocity_exit_time, p_mA_timeout); - rightPID.exit_condition_set(p_small_exit_time, p_small_error.convert(okapi::inch), p_big_exit_time, p_big_error.convert(okapi::inch), p_velocity_exit_time, p_mA_timeout); +void Drive::drive_exit_condition_set(int p_small_exit_time, okapi::QLength p_small_error, int p_big_exit_time, okapi::QLength p_big_error, int p_velocity_exit_time, int p_mA_timeout) { + pid_left.exit_condition_set(p_small_exit_time, p_small_error.convert(okapi::inch), p_big_exit_time, p_big_error.convert(okapi::inch), p_velocity_exit_time, p_mA_timeout); + pid_right.exit_condition_set(p_small_exit_time, p_small_error.convert(okapi::inch), p_big_exit_time, p_big_error.convert(okapi::inch), p_velocity_exit_time, p_mA_timeout); } -void Drive::set_turn_exit_condition(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout) { - turnPID.exit_condition_set(p_small_exit_time, p_small_error, p_big_exit_time, p_big_error, p_velocity_exit_time, p_mA_timeout); +void Drive::turn_exit_condition_set(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout) { + pid_turn.exit_condition_set(p_small_exit_time, p_small_error, p_big_exit_time, p_big_error, p_velocity_exit_time, p_mA_timeout); } -void Drive::set_swing_exit_condition(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout) { - swingPID.exit_condition_set(p_small_exit_time, p_small_error, p_big_exit_time, p_big_error, p_velocity_exit_time, p_mA_timeout); +void Drive::swing_exit_condition_set(int p_small_exit_time, double p_small_error, int p_big_exit_time, double p_big_error, int p_velocity_exit_time, int p_mA_timeout) { + pid_swing.exit_condition_set(p_small_exit_time, p_small_error, p_big_exit_time, p_big_error, p_velocity_exit_time, p_mA_timeout); } // User wrapper for exit condition -void Drive::wait_drive() { +void Drive::drive_wait_exit() { // Let the PID run at least 1 iteration pros::delay(util::DELAY_TIME); @@ -30,11 +30,11 @@ void Drive::wait_drive() { e_exit_output left_exit = RUNNING; e_exit_output right_exit = RUNNING; while (left_exit == RUNNING || right_exit == RUNNING) { - left_exit = left_exit != RUNNING ? left_exit : leftPID.exit_condition(left_motors[0]); - right_exit = right_exit != RUNNING ? right_exit : rightPID.exit_condition(right_motors[0]); + left_exit = left_exit != RUNNING ? left_exit : pid_left.exit_condition(motors_left[0]); + right_exit = right_exit != RUNNING ? right_exit : pid_right.exit_condition(motors_right[0]); pros::delay(util::DELAY_TIME); } - if (print_toggle) std::cout << " Left: " << exit_to_string(left_exit) << " Exit, error: " << leftPID.error << ". Right: " << exit_to_string(right_exit) << " Exit, error: " << rightPID.error << ".\n"; + if (print_toggle) std::cout << " Left: " << exit_to_string(left_exit) << " Exit, error: " << pid_left.error << ". Right: " << exit_to_string(right_exit) << " Exit, error: " << pid_right.error << ".\n"; if (left_exit == mA_EXIT || left_exit == VELOCITY_EXIT || right_exit == mA_EXIT || right_exit == VELOCITY_EXIT) { interfered = true; @@ -45,10 +45,10 @@ void Drive::wait_drive() { else if (mode == TURN) { e_exit_output turn_exit = RUNNING; while (turn_exit == RUNNING) { - turn_exit = turn_exit != RUNNING ? turn_exit : turnPID.exit_condition({left_motors[0], right_motors[0]}); + turn_exit = turn_exit != RUNNING ? turn_exit : pid_turn.exit_condition({motors_left[0], motors_right[0]}); pros::delay(util::DELAY_TIME); } - if (print_toggle) std::cout << " Turn: " << exit_to_string(turn_exit) << " Exit, error:" << turnPID.error << ".\n"; + if (print_toggle) std::cout << " Turn: " << exit_to_string(turn_exit) << " Exit, error:" << pid_turn.error << ".\n"; if (turn_exit == mA_EXIT || turn_exit == VELOCITY_EXIT) { interfered = true; @@ -58,12 +58,12 @@ void Drive::wait_drive() { // Swing Exit else if (mode == SWING) { e_exit_output swing_exit = RUNNING; - pros::Motor& sensor = current_swing == ez::LEFT_SWING ? left_motors[0] : right_motors[0]; + pros::Motor& sensor = swing_current == ez::LEFT_SWING ? motors_left[0] : motors_right[0]; while (swing_exit == RUNNING) { - swing_exit = swing_exit != RUNNING ? swing_exit : swingPID.exit_condition(sensor); + swing_exit = swing_exit != RUNNING ? swing_exit : pid_swing.exit_condition(sensor); pros::delay(util::DELAY_TIME); } - if (print_toggle) std::cout << " Swing: " << exit_to_string(swing_exit) << " Exit, error:" << swingPID.error << ".\n"; + if (print_toggle) std::cout << " Swing: " << exit_to_string(swing_exit) << " Exit, error:" << pid_swing.error << ".\n"; if (swing_exit == mA_EXIT || swing_exit == VELOCITY_EXIT) { interfered = true; @@ -71,14 +71,14 @@ void Drive::wait_drive() { } } -void Drive::wait_until_drive(double target) { +void Drive::drive_wait_until(double target) { // If robot is driving... if (mode == DRIVE) { // Calculate error between current and target (target needs to be an in between position) - int l_tar = l_start + target; - int r_tar = r_start + target; - int l_error = l_tar - left_sensor(); - int r_error = r_tar - right_sensor(); + int l_tar = start_left + target; + int r_tar = start_right + target; + int l_error = l_tar - sensor_left(); + int r_error = r_tar - sensor_right(); int l_sgn = util::sign(l_error); int r_sgn = util::sign(r_error); @@ -86,14 +86,14 @@ void Drive::wait_until_drive(double target) { e_exit_output right_exit = RUNNING; while (true) { - l_error = l_tar - left_sensor(); - r_error = r_tar - right_sensor(); + l_error = l_tar - sensor_left(); + r_error = r_tar - sensor_right(); // Before robot has reached target, use the exit conditions to avoid getting stuck in this while loop if (util::sign(l_error) == l_sgn || util::sign(r_error) == r_sgn) { if (left_exit == RUNNING || right_exit == RUNNING) { - left_exit = left_exit != RUNNING ? left_exit : leftPID.exit_condition(left_motors[0]); - right_exit = right_exit != RUNNING ? right_exit : rightPID.exit_condition(right_motors[0]); + left_exit = left_exit != RUNNING ? left_exit : pid_left.exit_condition(motors_left[0]); + right_exit = right_exit != RUNNING ? right_exit : pid_right.exit_condition(motors_right[0]); pros::delay(util::DELAY_TIME); } else { if (print_toggle) std::cout << " Left: " << exit_to_string(left_exit) << " Wait Until Exit. Right: " << exit_to_string(right_exit) << " Wait Until Exit.\n"; @@ -115,42 +115,42 @@ void Drive::wait_until_drive(double target) { } } -void Drive::wait_until(okapi::QLength target) { +void Drive::drive_wait_distance(okapi::QLength target) { // If robot is driving... if (mode == DRIVE) { - wait_until_drive(target.convert(okapi::inch)); + drive_wait_until(target.convert(okapi::inch)); } else { printf("QLength not supported for turn or swing!\n"); } } // Function to wait until a certain position is reached. Wrapper for exit condition. -void Drive::wait_until(double target) { +void Drive::drive_wait_distance(double target) { // If robot is driving... if (mode == DRIVE) { - wait_until_drive(target); + drive_wait_until(target); } // If robot is turning or swinging... else if (mode == TURN || mode == SWING) { // Calculate error between current and target (target needs to be an in between position) - int g_error = target - get_gyro(); + int g_error = target - imu_get(); int g_sgn = util::sign(g_error); e_exit_output turn_exit = RUNNING; e_exit_output swing_exit = RUNNING; - pros::Motor& sensor = current_swing == ez::LEFT_SWING ? left_motors[0] : right_motors[0]; + pros::Motor& sensor = swing_current == ez::LEFT_SWING ? motors_left[0] : motors_right[0]; while (true) { - g_error = target - get_gyro(); + g_error = target - imu_get(); // If turning... if (mode == TURN) { // Before robot has reached target, use the exit conditions to avoid getting stuck in this while loop if (util::sign(g_error) == g_sgn) { if (turn_exit == RUNNING) { - turn_exit = turn_exit != RUNNING ? turn_exit : turnPID.exit_condition({left_motors[0], right_motors[0]}); + turn_exit = turn_exit != RUNNING ? turn_exit : pid_turn.exit_condition({motors_left[0], motors_right[0]}); pros::delay(util::DELAY_TIME); } else { if (print_toggle) std::cout << " Turn: " << exit_to_string(turn_exit) << " Wait Until Exit.\n"; @@ -173,7 +173,7 @@ void Drive::wait_until(double target) { // Before robot has reached target, use the exit conditions to avoid getting stuck in this while loop if (util::sign(g_error) == g_sgn) { if (swing_exit == RUNNING) { - swing_exit = swing_exit != RUNNING ? swing_exit : swingPID.exit_condition(sensor); + swing_exit = swing_exit != RUNNING ? swing_exit : pid_swing.exit_condition(sensor); pros::delay(util::DELAY_TIME); } else { if (print_toggle) std::cout << " Swing: " << exit_to_string(swing_exit) << " Wait Until Exit.\n"; diff --git a/src/EZ-Template/drive/pid_tasks.cpp b/src/EZ-Template/drive/pid_tasks.cpp index 602f42f2..694dc32c 100644 --- a/src/EZ-Template/drive/pid_tasks.cpp +++ b/src/EZ-Template/drive/pid_tasks.cpp @@ -12,20 +12,20 @@ using namespace ez; void Drive::ez_auto_task() { while (true) { // Autonomous PID - if (get_mode() == DRIVE) - drive_pid_task(); - else if (get_mode() == TURN) - turn_pid_task(); - else if (get_mode() == SWING) - swing_pid_task(); + if (mode_get() == DRIVE) + pid_drive_task(); + else if (mode_get() == TURN) + pid_turn_task(); + else if (mode_get() == SWING) + pid_swing_task(); - util::AUTON_RAN = get_mode() != DISABLE ? true : false; + util::AUTON_RAN = mode_get() != DISABLE ? true : false; /* if (pros::competition::is_autonomous() && !util::AUTON_RAN) util::AUTON_RAN = true; else if (!pros::competition::is_autonomous()) - set_mode(DISABLE); + mode_set(DISABLE); */ pros::delay(util::DELAY_TIME); @@ -33,23 +33,23 @@ void Drive::ez_auto_task() { } // Drive PID task -void Drive::drive_pid_task() { +void Drive::pid_drive_task() { // Compute PID - leftPID.compute(left_sensor()); - rightPID.compute(right_sensor()); + pid_left.compute(sensor_left()); + pid_right.compute(sensor_right()); - headingPID.compute(get_gyro()); + pid_heading.compute(imu_get()); // Compute slew - double l_slew_out = slew_calculate(left_slew, left_sensor()); - double r_slew_out = slew_calculate(right_slew, right_sensor()); + double l_slew_out = slew_calculate(slew_left, sensor_left()); + double r_slew_out = slew_calculate(slew_right, sensor_right()); - // Clip leftPID and rightPID to slew (if slew is disabled, it returns max_speed) - double l_drive_out = util::clamp_number(leftPID.output, l_slew_out, -l_slew_out); - double r_drive_out = util::clamp_number(rightPID.output, r_slew_out, -r_slew_out); + // Clip pid_left and pid_right to slew (if slew is disabled, it returns speed_max) + double l_drive_out = util::clamp_number(pid_left.output, l_slew_out, -l_slew_out); + double r_drive_out = util::clamp_number(pid_right.output, r_slew_out, -r_slew_out); // Toggle heading - double gyro_out = heading_on ? headingPID.output : 0; + double gyro_out = heading_on ? pid_heading.output : 0; // Combine heading and drive double l_out = l_drive_out + gyro_out; @@ -57,47 +57,47 @@ void Drive::drive_pid_task() { // Set motors if (drive_toggle) - private_set_tank(l_out, r_out); + tank_set_private(l_out, r_out); } // Turn PID task -void Drive::turn_pid_task() { +void Drive::pid_turn_task() { // Compute PID - turnPID.compute(get_gyro()); + pid_turn.compute(imu_get()); // Clip gyroPID to max speed - double gyro_out = util::clamp_number(turnPID.output, max_speed, -max_speed); + double gyro_out = util::clamp_number(pid_turn.output, speed_max, -speed_max); // Clip the speed of the turn when the robot is within StartI, only do this when target is larger then StartI - if (turnPID.constants.ki != 0 && (fabs(turnPID.target_get()) > turnPID.constants.start_i && fabs(turnPID.error) < turnPID.constants.start_i)) { - if (get_turn_min() != 0) - gyro_out = util::clamp_number(gyro_out, get_turn_min(), -get_turn_min()); + if (pid_turn.constants.ki != 0 && (fabs(pid_turn.target_get()) > pid_turn.constants.start_i && fabs(pid_turn.error) < pid_turn.constants.start_i)) { + if (turn_min_get() != 0) + gyro_out = util::clamp_number(gyro_out, turn_min_get(), -turn_min_get()); } // Set motors if (drive_toggle) - private_set_tank(gyro_out, -gyro_out); + tank_set_private(gyro_out, -gyro_out); } // Swing PID task -void Drive::swing_pid_task() { +void Drive::pid_swing_task() { // Compute PID - swingPID.compute(get_gyro()); + pid_swing.compute(imu_get()); - // Clip swingPID to max speed - double swing_out = util::clamp_number(swingPID.output, max_speed, -max_speed); + // Clip pid_swing to max speed + double swing_out = util::clamp_number(pid_swing.output, speed_max, -speed_max); // Clip the speed of the turn when the robot is within StartI, only do this when target is larger then StartI - if (swingPID.constants.ki != 0 && (fabs(swingPID.target_get()) > swingPID.constants.start_i && fabs(swingPID.error) < swingPID.constants.start_i)) { - if (get_swing_min() != 0) - swing_out = util::clamp_number(swing_out, get_swing_min(), -get_swing_min()); + if (pid_swing.constants.ki != 0 && (fabs(pid_swing.target_get()) > pid_swing.constants.start_i && fabs(pid_swing.error) < pid_swing.constants.start_i)) { + if (swing_min_get() != 0) + swing_out = util::clamp_number(swing_out, swing_min_get(), -swing_min_get()); } if (drive_toggle) { // Check if left or right swing, then set motors accordingly - if (current_swing == LEFT_SWING) - private_set_tank(swing_out, 0); - else if (current_swing == RIGHT_SWING) - private_set_tank(0, -swing_out); + if (swing_current == LEFT_SWING) + tank_set_private(swing_out, 0); + else if (swing_current == RIGHT_SWING) + tank_set_private(0, -swing_out); } } diff --git a/src/EZ-Template/drive/pto.cpp b/src/EZ-Template/drive/pto.cpp index 6aa24fdc..f7311014 100644 --- a/src/EZ-Template/drive/pto.cpp +++ b/src/EZ-Template/drive/pto.cpp @@ -23,7 +23,7 @@ void Drive::pto_add(std::vector pto_list) { if (pto_check(i)) return; // Return if the first index was used (this motor is used for velocity) - if (i.get_port() == left_motors[0].get_port() || i.get_port() == right_motors[0].get_port()) { + if (i.get_port() == motors_left[0].get_port() || i.get_port() == motors_right[0].get_port()) { printf("You cannot PTO the first index!\n"); return; } diff --git a/src/EZ-Template/drive/set_pid.cpp b/src/EZ-Template/drive/set_pid.cpp index 5c90a8cb..71cd16c1 100644 --- a/src/EZ-Template/drive/set_pid.cpp +++ b/src/EZ-Template/drive/set_pid.cpp @@ -7,62 +7,62 @@ file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" // Set PID constants -void Drive::set_drive_pid_constants(double p, double i, double d, double p_start_i) { - set_drive_forward_pid_constants(p, i, d, p_start_i); - set_drive_backwards_pid_constants(p, i, d, p_start_i); +void Drive::pid_drive_constants_set(double p, double i, double d, double p_start_i) { + pid_drive_forward_constants_set(p, i, d, p_start_i); + pid_drive_backwards_constants_set(p, i, d, p_start_i); } -void Drive::set_drive_forward_pid_constants(double p, double i, double d, double p_start_i) { - forward_drivePID.constants_set(p, i, d, p_start_i); +void Drive::pid_drive_forward_constants_set(double p, double i, double d, double p_start_i) { + pid_forward_drive.constants_set(p, i, d, p_start_i); } -void Drive::set_drive_backwards_pid_constants(double p, double i, double d, double p_start_i) { - backward_drivePID.constants_set(p, i, d, p_start_i); +void Drive::pid_drive_backwards_constants_set(double p, double i, double d, double p_start_i) { + pid_backward_drive.constants_set(p, i, d, p_start_i); } -void Drive::set_turn_pid_constants(double p, double i, double d, double p_start_i) { - turnPID.constants_set(p, i, d, p_start_i); +void Drive::pid_turn_constants_set(double p, double i, double d, double p_start_i) { + pid_turn.constants_set(p, i, d, p_start_i); } -void Drive::set_swing_pid_constants(double p, double i, double d, double p_start_i) { - swingPID.constants_set(p, i, d, p_start_i); +void Drive::pid_swing_constants_set(double p, double i, double d, double p_start_i) { + pid_swing.constants_set(p, i, d, p_start_i); } -void Drive::set_heading_pid_constants(double p, double i, double d, double p_start_i) { - headingPID.constants_set(p, i, d, p_start_i); +void Drive::pid_heading_constants_set(double p, double i, double d, double p_start_i) { + pid_heading.constants_set(p, i, d, p_start_i); } // Updates max speed -void Drive::set_max_speed(int speed) { - max_speed = util::clamp_number(abs(speed), 127, -127); +void Drive::max_speed_set(int speed) { + speed_max = util::clamp_number(abs(speed), 127, -127); } -void Drive::reset_pid_targets() { - headingPID.target_set(0); - leftPID.target_set(0); - rightPID.target_set(0); - forward_drivePID.target_set(0); - backward_drivePID.target_set(0); - turnPID.target_set(0); +void Drive::pid_targets_reset() { + pid_heading.target_set(0); + pid_left.target_set(0); + pid_right.target_set(0); + pid_forward_drive.target_set(0); + pid_backward_drive.target_set(0); + pid_turn.target_set(0); } -void Drive::set_angle(double angle) { - headingPID.target_set(angle); - reset_gyro(angle); +void Drive::angle_set(double angle) { + pid_heading.target_set(angle); + imu_reset(angle); } -void Drive::set_mode(e_mode p_mode) { mode = p_mode; } +void Drive::mode_set(e_mode p_mode) { mode = p_mode; } -void Drive::set_turn_min(int min) { turn_min = abs(min); } -int Drive::get_turn_min() { return turn_min; } +void Drive::turn_min_set(int min) { turn_min = abs(min); } +int Drive::turn_min_get() { return turn_min; } -void Drive::set_swing_min(int min) { swing_min = abs(min); } -int Drive::get_swing_min() { return swing_min; } +void Drive::swing_min_set(int min) { swing_min = abs(min); } +int Drive::swing_min_get() { return swing_min; } -e_mode Drive::get_mode() { return mode; } +e_mode Drive::mode_get() { return mode; } // Set drive PID -void Drive::set_drive_pid(okapi::QLength p_target, int speed, bool slew_on, bool toggle_heading) { +void Drive::pid_drive_set(okapi::QLength p_target, int speed, bool slew_on, bool toggle_heading) { double target = p_target.convert(okapi::inch); // Print targets @@ -71,84 +71,84 @@ void Drive::set_drive_pid(okapi::QLength p_target, int speed, bool slew_on, bool if (print_toggle) printf("\n"); // Global setup - set_max_speed(speed); + max_speed_set(speed); heading_on = toggle_heading; bool is_backwards = false; - l_start = left_sensor(); - r_start = right_sensor(); + start_left = sensor_left(); + start_right = sensor_right(); double l_target_encoder, r_target_encoder; // Figure actual target value - l_target_encoder = l_start + target; - r_target_encoder = r_start + target; + l_target_encoder = start_left + target; + r_target_encoder = start_right + target; // Figure out if going forward or backward - if (l_target_encoder < l_start && r_target_encoder < r_start) { - auto consts = backward_drivePID.constants_get(); - leftPID.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); - rightPID.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); + if (l_target_encoder < start_left && r_target_encoder < start_right) { + auto consts = pid_backward_drive.constants_get(); + pid_left.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); + pid_right.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); is_backwards = true; } else { - auto consts = forward_drivePID.constants_get(); - leftPID.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); - rightPID.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); + auto consts = pid_forward_drive.constants_get(); + pid_left.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); + pid_right.constants_set(consts.kp, consts.ki, consts.kd, consts.start_i); is_backwards = false; } // Set PID targets - leftPID.target_set(l_target_encoder); - rightPID.target_set(r_target_encoder); + pid_left.target_set(l_target_encoder); + pid_right.target_set(r_target_encoder); // Initialize slew - slew_initialize(left_slew, slew_on, max_speed, l_target_encoder, left_sensor(), l_start, is_backwards); - slew_initialize(right_slew, slew_on, max_speed, r_target_encoder, right_sensor(), r_start, is_backwards); + slew_initialize(slew_left, slew_on, speed_max, l_target_encoder, sensor_left(), start_left, is_backwards); + slew_initialize(slew_right, slew_on, speed_max, r_target_encoder, sensor_right(), start_right, is_backwards); // Run task - set_mode(DRIVE); + mode_set(DRIVE); } // Set turn PID -void Drive::set_turn_pid(double target, int speed) { +void Drive::pid_turn_set(double target, int speed) { // Print targets if (print_toggle) printf("Turn Started... Target Value: %f\n", target); // Set PID targets - turnPID.target_set(target); - headingPID.target_set(target); // Update heading target for next drive motion - set_max_speed(speed); + pid_turn.target_set(target); + pid_heading.target_set(target); // Update heading target for next drive motion + max_speed_set(speed); // Run task - set_mode(TURN); + mode_set(TURN); } -void Drive::set_relative_turn_pid(double target, int speed) { +void Drive::pid_relative_turn_set(double target, int speed) { // Compute absolute target by adding to current heading - double absolute_target = turnPID.target_get() + target; + double absolute_target = pid_turn.target_get() + target; // Print targets if (print_toggle) printf("Turn Started... Target Value: %f\n", absolute_target); // Set PID targets - turnPID.target_set(absolute_target); - headingPID.target_set(absolute_target); - set_max_speed(speed); + pid_turn.target_set(absolute_target); + pid_heading.target_set(absolute_target); + max_speed_set(speed); // Run task - set_mode(TURN); + mode_set(TURN); } // Set swing PID -void Drive::set_swing_pid(e_swing type, double target, int speed) { +void Drive::pid_swing_set(e_swing type, double target, int speed) { // Print targets if (print_toggle) printf("Swing Started... Target Value: %f\n", target); - current_swing = type; + swing_current = type; // Set PID targets - swingPID.target_set(target); - headingPID.target_set(target); // Update heading target for next drive motion - set_max_speed(speed); + pid_swing.target_set(target); + pid_heading.target_set(target); // Update heading target for next drive motion + max_speed_set(speed); // Run task - set_mode(SWING); + mode_set(SWING); } diff --git a/src/EZ-Template/drive/slew.cpp b/src/EZ-Template/drive/slew.cpp index f4f7bfeb..06b84f35 100644 --- a/src/EZ-Template/drive/slew.cpp +++ b/src/EZ-Template/drive/slew.cpp @@ -9,25 +9,25 @@ file, You can obtain one at http://mozilla.org/MPL/2.0/. using namespace ez; // Set minimum power -void Drive::set_slew_min_power(int fwd, int rev) { +void Drive::slew_min_power_set(int fwd, int rev) { SLEW_MIN_POWER[0] = abs(fwd); SLEW_MIN_POWER[1] = abs(rev); } // Set distance to slew for -void Drive::set_slew_distance(okapi::QLength fwd, okapi::QLength rev) { +void Drive::slew_distance_set(okapi::QLength fwd, okapi::QLength rev) { SLEW_DISTANCE[0] = fabs(fwd.convert(okapi::inch)); SLEW_DISTANCE[1] = fabs(rev.convert(okapi::inch)); } // Initialize slew -void Drive::slew_initialize(slew_ &input, bool slew_on, double max_speed, double target, double current, double start, bool backwards) { +void Drive::slew_initialize(slew_ &input, bool slew_on, double speed_max, double target, double current, double start, bool backwards) { input.enabled = slew_on; - input.max_speed = max_speed; + input.speed_max = speed_max; input.sign = util::sign(target - current); input.x_intercept = start + ((SLEW_DISTANCE[backwards] * input.sign)); - input.y_intercept = max_speed * input.sign; + input.y_intercept = speed_max * input.sign; input.slope = ((input.sign * SLEW_MIN_POWER[backwards]) - input.y_intercept) / (input.x_intercept - 0 - start); // y2-y1 / x2-x1 } @@ -47,5 +47,5 @@ double Drive::slew_calculate(slew_ &input, double current) { return ((input.slope * input.error) + input.y_intercept) * input.sign; } // When slew is completed, return max speed - return max_speed; + return speed_max; } diff --git a/src/EZ-Template/drive/user_input.cpp b/src/EZ-Template/drive/user_input.cpp index f9b38b19..fceb2bdc 100644 --- a/src/EZ-Template/drive/user_input.cpp +++ b/src/EZ-Template/drive/user_input.cpp @@ -7,16 +7,16 @@ file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" // Set curve defaults -void Drive::set_curve_default(double left, double right) { - left_curve_scale = left; - right_curve_scale = right; +void Drive::curve_set_default(double left, double right) { + curve_left_scale = left; + curve_right_scale = right; - save_l_curve_sd(); - save_r_curve_sd(); + curve_left_save_sd(); + curve_right_save_sd(); } // Initialize curve SD card -void Drive::init_curve_sd() { +void Drive::curve_init_sd() { // If no SD card, return if (!ez::util::SD_CARD_ACTIVE) return; @@ -25,12 +25,12 @@ void Drive::init_curve_sd() { if ((l_usd_file_read = fopen("/usd/left_curve.txt", "r"))) { char l_buf[5]; fread(l_buf, 1, 5, l_usd_file_read); - left_curve_scale = std::stof(l_buf); + curve_left_scale = std::stof(l_buf); fclose(l_usd_file_read); } // If file doesn't exist, create file else { - save_l_curve_sd(); // Writing to a file that doesn't exist creates the file + curve_left_save_sd(); // Writing to a file that doesn't exist creates the file printf("Created left_curve.txt\n"); } @@ -39,59 +39,59 @@ void Drive::init_curve_sd() { if ((r_usd_file_read = fopen("/usd/right_curve.txt", "r"))) { char l_buf[5]; fread(l_buf, 1, 5, r_usd_file_read); - right_curve_scale = std::stof(l_buf); + curve_right_scale = std::stof(l_buf); fclose(r_usd_file_read); } // If file doesn't exist, create file else { - save_r_curve_sd(); // Writing to a file that doesn't exist creates the file + curve_right_save_sd(); // Writing to a file that doesn't exist creates the file printf("Created right_curve.txt\n"); } } // Save new left curve to SD card -void Drive::save_l_curve_sd() { +void Drive::curve_left_save_sd() { // If no SD card, return if (!ez::util::SD_CARD_ACTIVE) return; FILE* usd_file_write = fopen("/usd/left_curve.txt", "w"); - std::string in_str = std::to_string(left_curve_scale); + std::string in_str = std::to_string(curve_left_scale); char const* in_c = in_str.c_str(); fputs(in_c, usd_file_write); fclose(usd_file_write); } // Save new right curve to SD card -void Drive::save_r_curve_sd() { +void Drive::curve_right_save_sd() { // If no SD card, return if (!ez::util::SD_CARD_ACTIVE) return; FILE* usd_file_write = fopen("/usd/right_curve.txt", "w"); - std::string in_str = std::to_string(right_curve_scale); + std::string in_str = std::to_string(curve_right_scale); char const* in_c = in_str.c_str(); fputs(in_c, usd_file_write); fclose(usd_file_write); } -void Drive::set_left_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase) { - l_increase_.button = increase; - l_decrease_.button = decrease; +void Drive::curve_buttons_left_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase) { + left_increase_.button = increase; + left_decrease_.button = decrease; } -void Drive::set_right_curve_buttons(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase) { - r_increase_.button = increase; - r_decrease_.button = decrease; +void Drive::curve_buttons_right_set(pros::controller_digital_e_t decrease, pros::controller_digital_e_t increase) { + right_increase_.button = increase; + right_decrease_.button = decrease; } // Increase / decrease left and right curves -void Drive::l_increase() { left_curve_scale += 0.1; } -void Drive::l_decrease() { - left_curve_scale -= 0.1; - left_curve_scale = left_curve_scale < 0 ? 0 : left_curve_scale; +void Drive::curve_left_scale_increase() { curve_left_scale += 0.1; } +void Drive::curve_left_scale_decrease() { + curve_left_scale -= 0.1; + curve_left_scale = curve_left_scale < 0 ? 0 : curve_left_scale; } -void Drive::r_increase() { right_curve_scale += 0.1; } -void Drive::r_decrease() { - right_curve_scale -= 0.1; - right_curve_scale = right_curve_scale < 0 ? 0 : right_curve_scale; +void Drive::curve_right_scale_increase() { curve_right_scale += 0.1; } +void Drive::curve_right_scale_decrease() { + curve_right_scale -= 0.1; + curve_right_scale = curve_right_scale < 0 ? 0 : curve_right_scale; } // Button press logic for increase/decrease curves @@ -133,32 +133,32 @@ void Drive::button_press(button_* input_name, int button, std::function } // Toggle modifying curves with controller -void Drive::toggle_modify_curve_with_controller(bool toggle) { disable_controller = toggle; } +void Drive::curve_toggle_modify_with_controller(bool toggle) { controller_disable = toggle; } // Modify curves with button presses and display them to contrller -void Drive::modify_curve_with_controller() { - if (!disable_controller) return; // True enables, false disables. - - button_press(&l_increase_, master.get_digital(l_increase_.button), ([this] { this->l_increase(); }), ([this] { this->save_l_curve_sd(); })); - button_press(&l_decrease_, master.get_digital(l_decrease_.button), ([this] { this->l_decrease(); }), ([this] { this->save_l_curve_sd(); })); - if (!is_tank) { - button_press(&r_increase_, master.get_digital(r_increase_.button), ([this] { this->r_increase(); }), ([this] { this->save_r_curve_sd(); })); - button_press(&r_decrease_, master.get_digital(r_decrease_.button), ([this] { this->r_decrease(); }), ([this] { this->save_r_curve_sd(); })); +void Drive::curve_modify_with_controller() { + if (!controller_disable) return; // True enables, false disables. + + button_press(&left_increase_, master.get_digital(left_increase_.button), ([this] { this->curve_left_scale_increase(); }), ([this] { this->curve_left_save_sd(); })); + button_press(&left_decrease_, master.get_digital(left_decrease_.button), ([this] { this->curve_left_scale_decrease(); }), ([this] { this->curve_left_save_sd(); })); + if (!tank_active) { + button_press(&right_increase_, master.get_digital(right_increase_.button), ([this] { this->curve_right_scale_increase(); }), ([this] { this->curve_right_save_sd(); })); + button_press(&right_decrease_, master.get_digital(right_decrease_.button), ([this] { this->curve_right_scale_decrease(); }), ([this] { this->curve_right_save_sd(); })); } - auto sr = std::to_string(right_curve_scale); - auto sl = std::to_string(left_curve_scale); - if (!is_tank) + auto sr = std::to_string(curve_right_scale); + auto sl = std::to_string(curve_left_scale); + if (!tank_active) master.set_text(2, 0, sl + " " + sr); else master.set_text(2, 0, sl); } // Left curve function -double Drive::left_curve_function(double x) { - if (left_curve_scale != 0) { +double Drive::curve_left_function(double x) { + if (curve_left_scale != 0) { // if (CURVE_TYPE) - return (powf(2.718, -(left_curve_scale / 10)) + powf(2.718, (fabs(x) - 127) / 10) * (1 - powf(2.718, -(left_curve_scale / 10)))) * x; + return (powf(2.718, -(curve_left_scale / 10)) + powf(2.718, (fabs(x) - 127) / 10) * (1 - powf(2.718, -(curve_left_scale / 10)))) * x; // else // return powf(2.718, ((abs(x)-127)*RIGHT_CURVE_SCALE)/100)*x; } @@ -166,10 +166,10 @@ double Drive::left_curve_function(double x) { } // Right curve fnuction -double Drive::right_curve_function(double x) { - if (right_curve_scale != 0) { +double Drive::curve_right_function(double x) { + if (curve_right_scale != 0) { // if (CURVE_TYPE) - return (powf(2.718, -(right_curve_scale / 10)) + powf(2.718, (fabs(x) - 127) / 10) * (1 - powf(2.718, -(right_curve_scale / 10)))) * x; + return (powf(2.718, -(curve_right_scale / 10)) + powf(2.718, (fabs(x) - 127) / 10) * (1 - powf(2.718, -(curve_right_scale / 10)))) * x; // else // return powf(2.718, ((abs(x)-127)*RIGHT_CURVE_SCALE)/100)*x; } @@ -177,104 +177,104 @@ double Drive::right_curve_function(double x) { } // Set active brake constant -void Drive::set_active_brake(double kp) { +void Drive::active_brake_set(double kp) { active_brake_kp = kp; - reset_drive_sensor(); + drive_sensors_reset(); } // Set joystick threshold -void Drive::set_joystick_threshold(int threshold) { JOYSTICK_THRESHOLD = abs(threshold); } +void Drive::joystick_threshold_set(int threshold) { JOYSTICK_THRESHOLD = abs(threshold); } -void Drive::reset_drive_sensors_opcontrol() { +void Drive::drive_sensors_reset_opcontrol() { if (util::AUTON_RAN) { - reset_drive_sensor(); + drive_sensors_reset(); util::AUTON_RAN = false; } } -void Drive::toggle_practice_mode(bool toggle) { practice_mode_is_on = toggle; } +void Drive::practice_mode_toggle(bool toggle) { practice_mode_is_on = toggle; } -void Drive::joy_thresh_opcontrol(int l_stick, int r_stick) { +void Drive::joystick_threshold_opcontrol(int l_stick, int r_stick) { // Check the motors are being set to power if (abs(l_stick) > 0 || abs(r_stick) > 0) { if (practice_mode_is_on && (abs(l_stick) > 120 || abs(r_stick) > 120)) - set_tank(0, 0); + tank_set(0, 0); else - set_tank(l_stick, r_stick); - if (active_brake_kp != 0) reset_drive_sensor(); + tank_set(l_stick, r_stick); + if (active_brake_kp != 0) drive_sensors_reset(); } // When joys are released, run active brake (P) on drive else { - set_tank((0 - left_sensor()) * active_brake_kp, (0 - right_sensor()) * active_brake_kp); + tank_set((0 - sensor_left()) * active_brake_kp, (0 - sensor_right()) * active_brake_kp); } } // Clip joysticks based on joystick threshold -int Drive::clipped_joystick(int joystick) { return abs(joystick) < JOYSTICK_THRESHOLD ? 0 : joystick; } +int Drive::joystick_clamped(int joystick) { return abs(joystick) < JOYSTICK_THRESHOLD ? 0 : joystick; } // Tank control void Drive::tank() { - is_tank = true; - reset_drive_sensors_opcontrol(); + tank_active = true; + drive_sensors_reset_opcontrol(); // Toggle for controller curve - modify_curve_with_controller(); + curve_modify_with_controller(); auto analog_left_value = master.get_analog(ANALOG_LEFT_Y); auto analog_right_value = master.get_analog(ANALOG_RIGHT_Y); // Put the joysticks through the curve function - int l_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_LEFT_Y))); - int r_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_RIGHT_Y))); + int l_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_LEFT_Y))); + int r_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_RIGHT_Y))); // Set robot to l_stick and r_stick, check joystick threshold, set active brake - joy_thresh_opcontrol(l_stick, r_stick); + joystick_threshold_opcontrol(l_stick, r_stick); } // Arcade standard void Drive::arcade_standard(e_type stick_type) { - is_tank = false; - reset_drive_sensors_opcontrol(); + tank_active = false; + drive_sensors_reset_opcontrol(); // Toggle for controller curve - modify_curve_with_controller(); + curve_modify_with_controller(); int fwd_stick, turn_stick; // Check arcade type (split vs single, normal vs flipped) if (stick_type == SPLIT) { // Put the joysticks through the curve function - fwd_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_LEFT_Y))); - turn_stick = right_curve_function(clipped_joystick(master.get_analog(ANALOG_RIGHT_X))); + fwd_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_LEFT_Y))); + turn_stick = curve_right_function(joystick_clamped(master.get_analog(ANALOG_RIGHT_X))); } else if (stick_type == SINGLE) { // Put the joysticks through the curve function - fwd_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_LEFT_Y))); - turn_stick = right_curve_function(clipped_joystick(master.get_analog(ANALOG_LEFT_X))); + fwd_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_LEFT_Y))); + turn_stick = curve_right_function(joystick_clamped(master.get_analog(ANALOG_LEFT_X))); } // Set robot to l_stick and r_stick, check joystick threshold, set active brake - joy_thresh_opcontrol(fwd_stick + turn_stick, fwd_stick - turn_stick); + joystick_threshold_opcontrol(fwd_stick + turn_stick, fwd_stick - turn_stick); } // Arcade control flipped void Drive::arcade_flipped(e_type stick_type) { - is_tank = false; - reset_drive_sensors_opcontrol(); + tank_active = false; + drive_sensors_reset_opcontrol(); // Toggle for controller curve - modify_curve_with_controller(); + curve_modify_with_controller(); int turn_stick, fwd_stick; // Check arcade type (split vs single, normal vs flipped) if (stick_type == SPLIT) { // Put the joysticks through the curve function - fwd_stick = right_curve_function(clipped_joystick(master.get_analog(ANALOG_RIGHT_Y))); - turn_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_LEFT_X))); + fwd_stick = curve_right_function(joystick_clamped(master.get_analog(ANALOG_RIGHT_Y))); + turn_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_LEFT_X))); } else if (stick_type == SINGLE) { // Put the joysticks through the curve function - fwd_stick = right_curve_function(clipped_joystick(master.get_analog(ANALOG_RIGHT_Y))); - turn_stick = left_curve_function(clipped_joystick(master.get_analog(ANALOG_RIGHT_X))); + fwd_stick = curve_right_function(joystick_clamped(master.get_analog(ANALOG_RIGHT_Y))); + turn_stick = curve_left_function(joystick_clamped(master.get_analog(ANALOG_RIGHT_X))); } // Set robot to l_stick and r_stick, check joystick threshold, set active brake - joy_thresh_opcontrol(fwd_stick + turn_stick, fwd_stick - turn_stick); + joystick_threshold_opcontrol(fwd_stick + turn_stick, fwd_stick - turn_stick); } diff --git a/src/autons.cpp b/src/autons.cpp index 56c921d4..e53204b1 100644 --- a/src/autons.cpp +++ b/src/autons.cpp @@ -1,21 +1,17 @@ #include "main.h" - ///// // For instalattion, upgrading, documentations and tutorials, check out website! // https://ez-robotics.github.io/EZ-Template/ ///// - -const int DRIVE_SPEED = 110; // This is 110/127 (around 87% of max speed). We don't suggest making this 127. - // If this is 127 and the robot tries to heading correct, it's only correcting by - // making one side slower. When this is 87%, it's correcting by making one side - // faster and one side slower, giving better heading correction. -const int TURN_SPEED = 90; +const int DRIVE_SPEED = 110; // This is 110/127 (around 87% of max speed). We don't suggest making this 127. + // If this is 127 and the robot tries to heading correct, it's only correcting by + // making one side slower. When this is 87%, it's correcting by making one side + // faster and one side slower, giving better heading correction. +const int TURN_SPEED = 90; const int SWING_SPEED = 90; - - /// // Constants /// @@ -24,22 +20,18 @@ const int SWING_SPEED = 90; // If the objects are light or the cog doesn't change much, then there isn't a concern here. void default_constants() { - chassis.set_turn_exit_condition(200, 3, 500, 7, 750, 750); - chassis.set_swing_exit_condition(200, 3, 500, 7, 750, 750); - chassis.set_drive_exit_condition(200, 1_in, 500, 3_in, 750, 750); - - chassis.set_slew_min_power(80, 80); - chassis.set_slew_distance(7_in, 7_in); - chassis.set_heading_pid_constants(3, 0, 20, 0); - chassis.set_drive_pid_constants(15, 0, 150); - chassis.set_turn_pid_constants(3, 0, 20, 0); - chassis.set_swing_pid_constants(5, 0, 30, 0); - + chassis.turn_exit_condition_set(200, 3, 500, 7, 750, 750); + chassis.swing_exit_condition_set(200, 3, 500, 7, 750, 750); + chassis.drive_exit_condition_set(200, 1_in, 500, 3_in, 750, 750); + + chassis.slew_min_power_set(80, 80); + chassis.slew_distance_set(7_in, 7_in); + chassis.pid_heading_constants_set(3, 0, 20, 0); + chassis.pid_drive_constants_set(15, 0, 150); + chassis.pid_turn_constants_set(3, 0, 20, 0); + chassis.pid_swing_constants_set(5, 0, 30, 0); } - - - /// // Drive Example /// @@ -49,19 +41,16 @@ void drive_example() { // The third parameter is a boolean (true or false) for enabling/disabling a slew at the start of drive motions // for slew, only enable it when the drive distance is greater then the slew distance + a few inches + chassis.pid_drive_set(24_in, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_drive_pid(24_in, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(-12_in, DRIVE_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-12_in, DRIVE_SPEED); - chassis.wait_drive(); - - chassis.set_drive_pid(-12_in, DRIVE_SPEED); - chassis.wait_drive(); + chassis.pid_drive_set(-12_in, DRIVE_SPEED); + chassis.drive_wait_exit(); } - - /// // Turn Example /// @@ -69,72 +58,64 @@ void turn_example() { // The first parameter is target degrees // The second parameter is max speed the robot will drive at + chassis.pid_turn_set(90, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(90, TURN_SPEED); - chassis.wait_drive(); - - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); } - - /// // Combining Turn + Drive /// void drive_and_turn() { - chassis.set_drive_pid(24_in, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(24_in, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(-45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(-45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-24_in, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(-24_in, DRIVE_SPEED, true); + chassis.drive_wait_exit(); } - - /// // Wait Until and Changing Max Speed /// void wait_until_change_speed() { - // wait_until will wait until the robot gets to a desired position - + // drive_wait_distance will wait until the robot gets to a desired position // When the robot gets to 6 inches, the robot will travel the remaining distance at a max speed of 40 - chassis.set_drive_pid(24_in, DRIVE_SPEED, true); - chassis.wait_until(6_in); - chassis.set_max_speed(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed - chassis.wait_drive(); + chassis.pid_drive_set(24_in, DRIVE_SPEED, true); + chassis.drive_wait_distance(6_in); + chassis.max_speed_set(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(-45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(-45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); // When the robot gets to -6 inches, the robot will travel the remaining distance at a max speed of 40 - chassis.set_drive_pid(-24_in, DRIVE_SPEED, true); - chassis.wait_until(-6_in); - chassis.set_max_speed(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed - chassis.wait_drive(); + chassis.pid_drive_set(-24_in, DRIVE_SPEED, true); + chassis.drive_wait_distance(-6_in); + chassis.max_speed_set(40); // After driving 6 inches at DRIVE_SPEED, the robot will go the remaining distance at 40 speed + chassis.drive_wait_exit(); } - - /// // Swing Example /// @@ -143,55 +124,50 @@ void swing_example() { // The second parameter is target degrees // The third parameter is speed of the moving side of the drive + chassis.pid_swing_set(ez::LEFT_SWING, 45, SWING_SPEED); + chassis.drive_wait_exit(); - chassis.set_swing_pid(ez::LEFT_SWING, 45, SWING_SPEED); - chassis.wait_drive(); - - chassis.set_drive_pid(24_in, DRIVE_SPEED, true); - chassis.wait_until(12); + chassis.pid_drive_set(24_in, DRIVE_SPEED, true); + chassis.drive_wait_distance(12); - chassis.set_swing_pid(ez::RIGHT_SWING, 0, SWING_SPEED); - chassis.wait_drive(); + chassis.pid_swing_set(ez::RIGHT_SWING, 0, SWING_SPEED); + chassis.drive_wait_exit(); } - - /// // Auto that tests everything /// void combining_movements() { - chassis.set_drive_pid(24_in, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(24_in, DRIVE_SPEED, true); + chassis.drive_wait_exit(); - chassis.set_turn_pid(45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_swing_pid(ez::RIGHT_SWING, -45, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_swing_set(ez::RIGHT_SWING, -45, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_turn_pid(0, TURN_SPEED); - chassis.wait_drive(); + chassis.pid_turn_set(0, TURN_SPEED); + chassis.drive_wait_exit(); - chassis.set_drive_pid(-24_in, DRIVE_SPEED, true); - chassis.wait_drive(); + chassis.pid_drive_set(-24_in, DRIVE_SPEED, true); + chassis.drive_wait_exit(); } - - /// // Interference example /// -void tug (int attempts) { - for (int i=0; i