Skip to content

Commit

Permalink
fix: looser tolerances
Browse files Browse the repository at this point in the history
  • Loading branch information
LouisAsanaka committed Jan 11, 2021
1 parent c4b66fc commit e629bf4
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 26 deletions.
2 changes: 1 addition & 1 deletion include/constants.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ constexpr double DRIVE_ENCODER_TARGET_ERROR = 40;
constexpr double DRIVE_ENCODER_TARGET_DERIV = 5;
constexpr okapi::QTime DRIVE_ENCODER_TARGET_TIME = 200_ms;

constexpr double STRAFING_DIST_TARGET_ERROR = 0.015;
constexpr double STRAFING_DIST_TARGET_ERROR = 0.02;
constexpr double STRAFING_DIST_TARGET_DERIV = 5;
constexpr okapi::QTime STRAFING_DIST_TARGET_TIME = 150_ms;

Expand Down
4 changes: 4 additions & 0 deletions include/main.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,12 @@ void opcontrol(void);
*/
#include <iostream>
#include <memory>
#include <algorithm>
#include <numeric>
#include <cmath>
#include <exception>
#include <string>
#include <sstream>
#endif

#endif // _PROS_MAIN_H_
40 changes: 18 additions & 22 deletions src/autonomous.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,6 @@

#include "gui.hpp"

#include <exception>
#include <string>
#include <sstream>

void autonomous() {
#if defined(RUN_WITHOUT_ROBOT) && RUN_WITHOUT_ROBOT
return;
Expand All @@ -28,24 +24,24 @@ void autonomous() {
rightSide3(true);
} else {
reset(0_m, 0_m, 0_deg, false);
std::shared_ptr<PurePursuitPath> path = std::make_shared<PurePursuitPath>(
std::vector<Pose2d>{
{0.6_m, 0_m, 0_deg},
{1_m, 1_m, 0_deg}
}, 0.02_m,
PurePursuitPath::Constraints{0.6, 1.0, 2.0}
);
double b = 0.98;
double a = 1 - b;
double tol = 0.001;
path->smoothen(a, b, tol);
path->fillPointInformation();

for (const auto& point : path->points) {
std::cout << point.pose.toString() << " => " << point.distanceFromStart << "m, " << point.curvature << " curvature, " << point.targetVelocity << " m/s" << std::endl;
}
robot::drive->controller->followPath(path, 0.3_m, 0.01_m, {0.01, 1.0, 15.0});
std::cout << Pose2d::fromOdomState(robot::drive->controller->getState()).toString() << std::endl;
// std::shared_ptr<PurePursuitPath> path = std::make_shared<PurePursuitPath>(
// std::vector<Pose2d>{
// {0.6_m, 0_m, 0_deg},
// {1_m, 1_m, 0_deg}
// }, 0.02_m,
// PurePursuitPath::Constraints{0.6, 1.0, 2.0}
// );
// double b = 0.98;
// double a = 1 - b;
// double tol = 0.001;
// path->smoothen(a, b, tol);
// path->fillPointInformation();

// for (const auto& point : path->points) {
// std::cout << point.pose.toString() << " => " << point.distanceFromStart << "m, " << point.curvature << " curvature, " << point.targetVelocity << " m/s" << std::endl;
// }
// robot::drive->controller->followPath(path, 0.3_m, 0.01_m, {0.01, 1.0, 15.0});
// std::cout << Pose2d::fromOdomState(robot::drive->controller->getState()).toString() << std::endl;
}

std::stringstream ss;
Expand Down
4 changes: 2 additions & 2 deletions src/opcontrol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@ void opcontrol() {
xDriveRegularOverride = !xDriveRegularOverride;
overrideLatch = true;
if (xDriveRegularOverride) {
master.rumble(".-");
master.rumble("..");
master.setText(0, 0, "Mode: robot");
} else {
master.rumble("-.");
master.rumble(".");
master.setText(0, 0, "Mode: field");
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/robot/conveyor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void Conveyor::loop() {
stop(Position::Top);
checkingForBalls.store(false, std::memory_order_release);
}
pros::delay(100);
pros::delay(50);
}
}
} // namespace robot

0 comments on commit e629bf4

Please sign in to comment.