Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix choreo path splitting #859

Merged
merged 2 commits into from
Oct 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 3 additions & 13 deletions lib/path/choreo_path.dart
Original file line number Diff line number Diff line change
Expand Up @@ -81,22 +81,12 @@ class ChoreoPath {
.map((e) => (e as num).toInt())
.toList();

if (splits.isNotEmpty) {
// First split
final splitTraj = PathPlannerTrajectory.fromStates(
path.trajectory.states.sublist(0, splits[0]));
final splitPath = ChoreoPath(
name: '$pathName.0',
trajectory: splitTraj,
fs: fs,
choreoDir: choreoDir,
eventMarkerTimes: [],
);
paths.add(splitPath);
if (splits.isEmpty || splits.first != 0) {
splits.insert(0, 0);
}

for (int i = 0; i < splits.length; i++) {
String name = '$pathName.${i + 1}';
String name = '$pathName.$i';

int startIdx = splits[i];
int endIdx;
Expand Down
16 changes: 9 additions & 7 deletions pathplannerlib-python/pathplannerlib/path.py
Original file line number Diff line number Diff line change
Expand Up @@ -580,18 +580,20 @@ def _loadChoreoTrajectoryIntoCache(trajectory_name: str) -> None:
fullPath.name = trajectory_name
PathPlannerPath._choreoPathCache[trajectory_name] = fullPath

splits = trajJson['splits']
for i in range(-1, len(splits)):
name = trajectory_name + '.' + str(i + 1)
splitsJson = trajJson['splits']
splits = [int(s) for s in splitsJson]
if len(splits) == 0 or int(splits[0]) != 0:
splits.insert(0, 0)

for i in range(len(splits)):
name = trajectory_name + '.' + str(i)
states = []

splitStartIdx = 0
if i != -1:
splitStartIdx = int(splits[i])
splitStartIdx = splits[i]

splitEndIdx = len(fullTrajStates)
if i < len(splits) - 1:
splitEndIdx = int(splits[i + 1])
splitEndIdx = splits[i + 1]

startTime = fullTrajStates[splitStartIdx].timeSeconds
endTime = fullTrajStates[splitEndIdx - 1].timeSeconds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -420,19 +420,25 @@ private static void loadChoreoTrajectoryIntoCache(String trajectoryName)
fullPath.name = trajectoryName;
choreoPathCache.put(trajectoryName, fullPath);

JSONArray splits = (JSONArray) trajJson.get("splits");
for (int i = -1; i < splits.size(); i++) {
String name = trajectoryName + "." + (i + 1);
JSONArray splitsJson = (JSONArray) trajJson.get("splits");
List<Integer> splits = new ArrayList<>();
for (Object o : splitsJson) {
splits.add(((Number) o).intValue());
}

if (splits.isEmpty() || splits.get(0) != 0) {
splits.add(0, 0);
}

for (int i = 0; i < splits.size(); i++) {
String name = trajectoryName + "." + i;
List<PathPlannerTrajectoryState> states = new ArrayList<>();

int splitStartIdx = 0;
if (i != -1) {
splitStartIdx = ((Number) splits.get(i)).intValue();
}
int splitStartIdx = splits.get(i);

int splitEndIdx = fullTrajStates.size();
if (i < splits.size() - 1) {
splitEndIdx = ((Number) splits.get(i + 1)).intValue();
splitEndIdx = splits.get(i + 1);
}

double startTime = fullTrajStates.get(splitStartIdx).timeSeconds;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,58 +243,63 @@ void PathPlannerPath::loadChoreoTrajectoryIntoCache(
fullPath->name = trajectoryName;
PathPlannerPath::getChoreoPathCache().emplace(trajectoryName, fullPath);

auto splits = trajJson.at("splits");
if (splits.is_array()) {
int splitsSize = static_cast<int>(splits.size());
for (int i = -1; i < splitsSize; i++) {
std::string name = trajectoryName + "." + std::to_string(i + 1);
std::vector < PathPlannerTrajectoryState > states;

size_t splitStartIdx = 0;
if (i != -1) {
splitStartIdx = splits[i].get<size_t>();
}
auto splitsJson = trajJson.at("splits");
std::vector < size_t > splits;

size_t splitEndIdx = fullTrajStates.size();
if (i < splitsSize) {
splitEndIdx = splits[i + 1].get<size_t>();
}
if (splitsJson.is_array()) {
for (auto split : splitsJson) {
splits.emplace_back(split.get<size_t>());
}
}

auto startTime = fullTrajStates[splitStartIdx].time;
auto endTime = fullTrajStates[splitEndIdx - 1].time;
for (size_t s = splitStartIdx; s < splitEndIdx; s++) {
states.emplace_back(
fullTrajStates[s].copyWithTime(
fullTrajStates[s].time - startTime));
}
if (splits.empty() || splits[0] != 0) {
splits.insert(splits.begin(), 0);
}

std::vector < std::shared_ptr < Event >> events;
for (auto originalEvent : fullEvents) {
if (originalEvent->getTimestamp() >= startTime
&& originalEvent->getTimestamp() < endTime) {
events.emplace_back(
originalEvent->copyWithTimestamp(
originalEvent->getTimestamp() - startTime));
}
}
for (size_t i = 0; i < splits.size(); i++) {
std::string name = trajectoryName + "." + std::to_string(i);
std::vector < PathPlannerTrajectoryState > states;

auto path =
std::make_shared < PathPlannerPath
> (PathConstraints::unlimitedConstraints(12_V), GoalEndState(
states[states.size() - 1].linearVelocity,
states[states.size() - 1].pose.Rotation()));
size_t splitStartIdx = splits[i];

std::vector < PathPoint > pathPoints;
for (auto state : states) {
pathPoints.emplace_back(state.pose.Translation());
size_t splitEndIdx = fullTrajStates.size();
if (i < splits.size()) {
splitEndIdx = splits[i + 1];
}

auto startTime = fullTrajStates[splitStartIdx].time;
auto endTime = fullTrajStates[splitEndIdx - 1].time;
for (size_t s = splitStartIdx; s < splitEndIdx; s++) {
states.emplace_back(
fullTrajStates[s].copyWithTime(
fullTrajStates[s].time - startTime));
}

std::vector < std::shared_ptr < Event >> events;
for (auto originalEvent : fullEvents) {
if (originalEvent->getTimestamp() >= startTime
&& originalEvent->getTimestamp() < endTime) {
events.emplace_back(
originalEvent->copyWithTimestamp(
originalEvent->getTimestamp() - startTime));
}
}

auto path = std::make_shared < PathPlannerPath
> (PathConstraints::unlimitedConstraints(12_V), GoalEndState(
states[states.size() - 1].linearVelocity,
states[states.size() - 1].pose.Rotation()));

path->m_allPoints = pathPoints;
path->m_isChoreoPath = true;
path->m_idealTrajectory = PathPlannerTrajectory(states, events);
path->name = name;
PathPlannerPath::getChoreoPathCache().emplace(name, path);
std::vector < PathPoint > pathPoints;
for (auto state : states) {
pathPoints.emplace_back(state.pose.Translation());
}

path->m_allPoints = pathPoints;
path->m_isChoreoPath = true;
path->m_idealTrajectory = PathPlannerTrajectory(states, events);
path->name = name;
PathPlannerPath::getChoreoPathCache().emplace(name, path);
}
}

Expand Down
Loading