Skip to content

Commit

Permalink
help why doesn't this work
Browse files Browse the repository at this point in the history
  • Loading branch information
ion098 committed Feb 20, 2024
1 parent 5844a17 commit b9a06a4
Show file tree
Hide file tree
Showing 6 changed files with 184 additions and 29 deletions.
22 changes: 20 additions & 2 deletions include/autonomous.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,27 @@
#define _AUTONOMOUS_HPP_

#include "main.hpp"
#include <map>
#include <utility>

void far_side_auton_awp();
void far_side_auton();

void near_side_auton_awp();
void near_side_auton();

void skills();

void tune_pid();

void set_up_auton_selector();

// {*Name*, {*Function*, *Description*}}
inline std::map<std::string, std::pair<void(*)(), std::string> > auton_list{
{"Far Side", {far_side_auton, "Does stuff"}},
{"Near Side", {near_side_auton, "Does stuff"}},
{"Skills", {skills, "Does stuff"}},
{"Tune PID", {tune_pid, "Does stuff"}}
};

inline std::string selected_auton = "Tune PID";

#endif
45 changes: 44 additions & 1 deletion include/globals.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,58 @@ inline pros::Motor lift_right(11, pros::E_MOTOR_GEAR_RED);
inline pros::Motor lift_left(-20, pros::E_MOTOR_GEAR_RED);
inline pros::Motor_Group lift({lift_left, lift_right});
inline pros::Motor flywheel_arm(-19, pros::E_MOTOR_GEAR_GREEN);
inline pros::Motor flywheel(-12, pros::E_MOTOR_GEAR_GREEN);
inline pros::Motor flywheel(-12, pros::E_MOTOR_GEAR_BLUE);
inline pros::ADIDigitalOut wings('H');
inline pros::ADIDigitalOut led('G');
inline pros::Controller master(CONTROLLER_MASTER);
inline pros::Imu inertial(11);
inline pros::Distance front_distance(17);

inline lemlib::Drivetrain_t drivetrain {
&left_wheels, // left drivetrain motors
&right_wheels, // right drivetrain motors
10.25, // track width
3.25, // wheel diameter
480 // wheel rpm
};

inline lemlib::OdomSensors_t sensors {
nullptr, // vertical tracking wheel 1
nullptr, // vertical tracking wheel 2
nullptr, // horizontal tracking wheel 1
nullptr, // horizontal tracking wheel 2
&inertial // inertial sensor
};

// forward/backward PID
inline lemlib::ChassisController_t lateralController {
8, // kP
30, // kD
1, // smallErrorRange
100, // smallErrorTimeout
3, // largeErrorRange
500, // largeErrorTimeout
5 // slew rate
};

// turning PID
inline lemlib::ChassisController_t angularController {
4, // kP
40, // kD
1, // smallErrorRange
100, // smallErrorTimeout
3, // largeErrorRange
500, // largeErrorTimeout
0 // slew rate
};

inline lemlib::Chassis chassis(drivetrain, lateralController, angularController, sensors);

//inline pros::Mutex hot_motor_list_lock;
//inline std::deque<std::string> hot_motor_list;

inline std::atomic<int> wing_count = 0;
inline std::atomic<int> flywheel_velocity = 80;

inline lv_obj_t* all_tabs;
inline lv_obj_t* motor_temp_page;
Expand Down
59 changes: 56 additions & 3 deletions src/autonomous.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#include "main.hpp"
#include <fstream>
#include <iostream>

/**
* Runs the user autonomous code. This function will be started in its own task
Expand All @@ -12,7 +14,13 @@
* from where it left off.
*/
void autonomous() {
pros::Task print_motor_task(monitor_temp);
std::cout << selected_auton;
auto it = auton_list.find(selected_auton);
if(it != auton_list.end()) {
it->second.first();
} else {
std::cout << "NO AUTON FOUND";
}
}

/*
Expand All @@ -23,10 +31,55 @@ Turns are relative to STARTING angle of robot, NOT the current angle
180
*/

void far_side_auton_awp() {
static lv_obj_t* auton_desc;

lv_res_t change_auton_action(lv_obj_t * list_btn) {
selected_auton = lv_list_get_btn_text(list_btn);
if(pros::usd::is_installed()) {
std::ofstream auton_file("usd/selected_auton");
if(auton_file.good()) {
auton_file << selected_auton;
}
}
lv_label_set_text(auton_desc, (selected_auton + ": " + auton_list[selected_auton].second).c_str());
return LV_RES_OK;
}

void near_side_auton_awp() {
void set_up_auton_selector() {
if(pros::usd::is_installed()) {
std::ifstream auton_file("usd/selected_auton");
if(auton_file.good()) {
auton_file >> selected_auton;
}
}

//set up auton selector
lv_obj_t* auton_select_list = lv_list_create(auton_select_page, nullptr);
lv_obj_set_size(auton_select_list, 200, 200);
lv_obj_align(auton_select_list, nullptr, LV_ALIGN_IN_TOP_LEFT, 20, 20);

auton_desc = lv_label_create(auton_select_page, NULL);
lv_obj_set_size(auton_desc, 200, 200);
lv_obj_align(auton_desc, nullptr, LV_ALIGN_IN_TOP_LEFT, 240, 20);
lv_label_set_long_mode(auton_desc, LV_LABEL_LONG_BREAK);

for(auto i : auton_list) {
lv_list_add(auton_select_list, nullptr, i.first.c_str(), &change_auton_action);
}
}

void far_side_auton() {

}

void near_side_auton() {

}

void tune_pid() {
chassis.moveTo(10, 0 , 10);
}

void skills() {

}
16 changes: 15 additions & 1 deletion src/initialize.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,8 @@
#include "main.hpp"
#include <fstream>




/**
* Runs initialization code. This occurs as soon as the program is started.
Expand All @@ -7,11 +11,21 @@
* to keep execution time for this mode under a few seconds.
*/
void initialize() {
all_tabs = lv_tabview_create(lv_scr_act(), NULL);

flywheel_arm.set_brake_mode(pros::E_MOTOR_BRAKE_HOLD);

all_tabs = lv_tabview_create(lv_scr_act(), nullptr);
motor_temp_page = lv_tabview_add_tab(all_tabs, "Motors");
auton_select_page = lv_tabview_add_tab(all_tabs, "Auton");

set_up_auton_selector();

pros::Task screen_task(monitor_temp);

chassis.calibrate();
}


/**
* Runs while the robot is in the disabled state of Field Management System or
* the VEX Competition Switch, following either autonomous or opcontrol. When
Expand Down
26 changes: 14 additions & 12 deletions src/motor_temp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

int line_num = 1;
void print_temp(pros::Motor &motor, std::string name, lv_obj_t* label) {
/*
static lv_style_t purple_style = lv_style_plain;
purple_style.body.main_color = LV_COLOR_BLACK;
purple_style.body.grad_color = LV_COLOR_BLACK;
Expand All @@ -27,24 +28,24 @@ void print_temp(pros::Motor &motor, std::string name, lv_obj_t* label) {
yellow_style.text.color = LV_COLOR_YELLOW;
green_style.text.color = LV_COLOR_GREEN;
blue_style.text.color = LV_COLOR_AQUA;

*/
int temp = static_cast<int>(motor.get_temperature());

std::string text;
if (temp >= 70) {
lv_label_set_style(label, &purple_style);
text += "#ff00ff ";
} else if (temp >= 65) {
lv_label_set_style(label, &red_style);
text += "#ff0000 ";
} else if (temp >= 60) {
lv_label_set_style(label, &orange_style);
text += "#ffa500 ";
} else if (temp >= 55) {
lv_label_set_style(label, &yellow_style);
text += "#ffff00 ";
} else if (temp >= 45) {
lv_label_set_style(label, &green_style);
text += "#00ff00 ";
} else {
lv_label_set_style(label, &blue_style);
text += "#00ffff ";
}
std::string text = name + ": " + std::to_string(temp) + "C";
text += " (Port " + std::to_string(motor.get_port()) + ")";
text += name + ": " + std::to_string(temp) + "C";
text += " (Port " + std::to_string(motor.get_port()) + ")#";

if(temp >= 55) {
Alert temp_alert = Alert(text);
Expand All @@ -59,8 +60,9 @@ void print_temp(pros::Motor &motor, std::string name, lv_obj_t* label) {
void monitor_temp() {
std::array<lv_obj_t*, 8> labels;
for(int i = 0; i < 8; i++) {
labels[i] = lv_label_create(motor_temp_page, NULL);
lv_obj_align(labels[i], NULL, LV_ALIGN_IN_TOP_LEFT, 10, 20 * i + 20);
labels[i] = lv_label_create(motor_temp_page, nullptr);
lv_obj_align(labels[i], nullptr, LV_ALIGN_IN_TOP_LEFT, 10, 20 * i + 20);
lv_label_set_recolor(labels[i], true);
}
while (true) {
print_temp(left_front, "drive lf", labels[0]);
Expand Down
45 changes: 35 additions & 10 deletions src/opcontrol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ double get_joystick(pros::controller_analog_e_t joystick, double curve = 1,
return joystick_val;
}

std::atomic<int> flywheel_velocity = 80;



void update_controller() {
Expand All @@ -34,10 +34,10 @@ void update_controller() {

text = "TV: ";
if(controls::fvw_is_reversed()) text += "-";
text += std::to_string(flywheel_velocity);
text += std::to_string(flywheel_velocity) + " ";
master.print(0, 0, text.c_str());
pros::delay(100);
int real_vel = static_cast<int>( std::round(flywheel.get_actual_velocity()) );
int real_vel = static_cast<int>( flywheel.get_actual_velocity() );
text = "AV: " + std::to_string(real_vel) + " ";
master.print(0, 7, text.c_str());
pros::delay(100);
Expand All @@ -63,10 +63,6 @@ void endgame_timer() {
controller_alerts.addAlert(Alert("15s left!!", Alert::Priority::HIGHEST));
}

void test_alert() {
pros::delay(15*1000);
controller_alerts.addAlert(Alert("test", Alert::Priority::HIGHEST));
}

/**
* Runs the operator control code. This function will be started in its own task
Expand All @@ -83,12 +79,39 @@ void test_alert() {
*/
void opcontrol() {
pros::Task controller_task(update_controller);
pros::Task screen_task(monitor_temp);
pros::Task endgame_task(endgame_timer);
pros::Task test_task(test_alert);

while(true) {

int time = 0;
//test auton
while(controls::fvw_up() && controls::fvw_down()
&& controls::lift_up() && controls::lift_down()) {
pros::delay(10);
time += 10;
if(time == 1000) {
controller_alerts.addAlert(Alert("Auton test in 1s!!!", Alert::Priority::HIGHEST, 1000));
}
if(time == 2000) {
controller_alerts.addAlert(Alert("Skills: A, Regular: X", Alert::Priority::HIGHEST, 1000));
bool skills = false;
bool regular = false;
while(!skills && !regular) {
skills = master.get_digital_new_press(pros::E_CONTROLLER_DIGITAL_A);
regular = master.get_digital_new_press(pros::E_CONTROLLER_DIGITAL_X);
}
pros::Task auton_tesk_task(autonomous);
if (skills) {
controller_alerts.addAlert(Alert("Skills", Alert::Priority::HIGHEST));
pros::delay(60 * 1000);
} else {
controller_alerts.addAlert(Alert("Regular Auton", Alert::Priority::HIGHEST));
pros::delay(15 * 1000);
}
auton_tesk_task.suspend();
}
}

//wing control
if(controls::wing_is_out()) {
wings.set_value(1);
Expand All @@ -109,7 +132,7 @@ void opcontrol() {
if(controls::fvw_up()) flywheel_velocity++;
if(controls::fvw_down()) flywheel_velocity--;
if(flywheel_velocity < 0) flywheel_velocity = 0;
if(flywheel_velocity > 200) flywheel_velocity = 200;
if(flywheel_velocity > 200) flywheel_velocity = 600;
if(controls::flywheel_is_on() && controls::fvw_is_reversed()) {
flywheel.move_velocity(-flywheel_velocity);
} else if (controls::flywheel_is_on()) {
Expand All @@ -127,8 +150,10 @@ void opcontrol() {
lift.brake();
if(lift.get_positions()[0] < 65) {
lift.set_brake_modes(pros::E_MOTOR_BRAKE_COAST);
led.set_value(1);
} else {
lift.set_brake_modes(pros::E_MOTOR_BRAKE_HOLD);
led.set_value(0);
}
}

Expand Down

0 comments on commit b9a06a4

Please sign in to comment.