Skip to content

Commit

Permalink
Fix null feedforwards for final trajectory state (#782)
Browse files Browse the repository at this point in the history
  • Loading branch information
mjansen4857 authored Oct 1, 2024
1 parent f5a2234 commit cd108d5
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 0 deletions.
3 changes: 3 additions & 0 deletions pathplannerlib-python/pathplannerlib/trajectory.py
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,9 @@ def __init__(self, path: Union[PathPlannerPath, None], starting_speeds: Union[Ch
self._events.append(ScheduleCommandEvent(prevState.timeSeconds, m.command))
unaddedMarkers.pop(0)

# Create feedforwards for the end state
self._states[-1].feedforwards = [DriveFeedforward(0, 0, 0)] * config.numModules

def getEvents(self) -> List[Event]:
"""
Get all the events to run while following this trajectory
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,11 @@ public PathPlannerTrajectory(
}
}
}

// Create feedforwards for the end state
for (int m = 0; m < config.numModules; m++) {
states.get(states.size() - 1).feedforwards[m] = new DriveFeedforward(0, 0, 0);
}
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,12 @@ PathPlannerTrajectory::PathPlannerTrajectory(
unaddedMarkers.erase(unaddedMarkers.begin());
}
}

// Create feedforwards for the end state
for (size_t m = 0; m < config.numModules; m++) {
m_states[m_states.size() - 1].feedforwards.emplace_back(
DriveFeedforward { 0_mps_sq, 0_N, 0_A });
}
}
}
}
Expand Down

0 comments on commit cd108d5

Please sign in to comment.