Skip to content

Commit

Permalink
why
Browse files Browse the repository at this point in the history
  • Loading branch information
mjansen4857 committed Oct 15, 2023
1 parent bb3ce87 commit 7fc395b
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include <stdexcept>
#include <frc2/command/Commands.h>
#include <frc/Filesystem.h>
#include <wpi/raw_istream.h>
#include <wpi/MemoryBuffer.h>

using namespace pathplanner;

Expand Down Expand Up @@ -267,14 +267,14 @@ frc2::CommandPtr AutoBuilder::buildAuto(std::string autoName) {
+ "/pathplanner/autos/" + autoName + ".auto";

std::error_code error_code;
wpi::raw_fd_istream input { filePath, error_code };
std::unique_ptr < wpi::MemoryBuffer > fileBuffer =
wpi::MemoryBuffer::GetFile(filePath, error_code);

if (error_code) {
if (fileBuffer == nullptr || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json;
input >> json;
wpi::json json = wpi::json::parse(fileBuffer->begin(), fileBuffer->end());

return getAutoCommandFromJson(json);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include "pathplanner/lib/auto/AutoBuilder.h"
#include "pathplanner/lib/util/PPLibTelemetry.h"
#include <frc/Filesystem.h>
#include <wpi/raw_istream.h>
#include <wpi/MemoryBuffer.h>

using namespace pathplanner;

Expand All @@ -22,14 +22,14 @@ std::vector<std::shared_ptr<PathPlannerPath>> PathPlannerAuto::getPathGroupFromA
+ "/pathplanner/autos/" + autoName + ".auto";

std::error_code error_code;
wpi::raw_fd_istream input { filePath, error_code };
std::unique_ptr < wpi::MemoryBuffer > fileBuffer =
wpi::MemoryBuffer::GetFile(filePath, error_code);

if (error_code) {
if (fileBuffer == nullptr || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json;
input >> json;
wpi::json json = wpi::json::parse(fileBuffer->begin(), fileBuffer->end());

return pathsFromCommandJson(json.at("command"));
}
Expand All @@ -39,14 +39,14 @@ frc::Pose2d PathPlannerAuto::getStartingPoseFromAutoFile(std::string autoName) {
+ "/pathplanner/autos/" + autoName + ".auto";

std::error_code error_code;
wpi::raw_fd_istream input { filePath, error_code };
std::unique_ptr < wpi::MemoryBuffer > fileBuffer =
wpi::MemoryBuffer::GetFile(filePath, error_code);

if (error_code) {
if (fileBuffer == nullptr || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json;
input >> json;
wpi::json json = wpi::json::parse(fileBuffer->begin(), fileBuffer->end());

return AutoBuilder::getStartingPoseFromJson(json.at("startingPose"));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include "pathplanner/lib/util/GeometryUtil.h"
#include "pathplanner/lib/util/PPLibTelemetry.h"
#include <frc/Filesystem.h>
#include <wpi/raw_istream.h>
#include <wpi/MemoryBuffer.h>
#include <limits>
#include <optional>

Expand Down Expand Up @@ -87,14 +87,14 @@ std::shared_ptr<PathPlannerPath> PathPlannerPath::fromPathFile(
+ "/pathplanner/paths/" + pathName + ".path";

std::error_code error_code;
wpi::raw_fd_istream input { filePath, error_code };
std::unique_ptr < wpi::MemoryBuffer > fileBuffer =
wpi::MemoryBuffer::GetFile(filePath, error_code);

if (error_code) {
if (fileBuffer == nullptr || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json;
input >> json;
wpi::json json = wpi::json::parse(fileBuffer->begin(), fileBuffer->end());

std::shared_ptr < PathPlannerPath > path = std::make_shared
< PathPlannerPath > (PathPlannerPath::fromJson(json));
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "pathplanner/lib/pathfinding/LocalADStar.h"
#include <cmath>
#include <frc/Filesystem.h>
#include <wpi/raw_istream.h>
#include <wpi/MemoryBuffer.h>
#include <wpi/json.h>
#include <chrono>
#include <frc/Errors.h>
Expand All @@ -26,12 +26,13 @@ LocalADStar::LocalADStar() : fieldLength(16.54), fieldWidth(8.02), nodeSize(
+ "/pathplanner/navgrid.json";

std::error_code error_code;
wpi::raw_fd_istream input { filePath, error_code };
std::unique_ptr < wpi::MemoryBuffer > fileBuffer =
wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!error_code) {
try {
wpi::json json;
input >> json;
wpi::json json = wpi::json::parse(fileBuffer->begin(),
fileBuffer->end());

nodeSize = json.at("nodeSizeMeters").get<double>();
wpi::json::const_reference grid = json.at("grid");
Expand Down

0 comments on commit 7fc395b

Please sign in to comment.