2020-12-26 14:12:05 -08:00
|
|
|
// Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
// the WPILib BSD license file in the root directory of this project.
|
2019-09-28 18:40:56 -04:00
|
|
|
|
|
|
|
|
#include "frc/trajectory/Trajectory.h"
|
|
|
|
|
|
2020-10-08 23:09:30 -04:00
|
|
|
#include <algorithm>
|
|
|
|
|
|
2019-11-02 13:35:03 -05:00
|
|
|
#include <wpi/json.h>
|
|
|
|
|
|
2020-08-06 23:57:39 -07:00
|
|
|
#include "units/math.h"
|
|
|
|
|
|
2019-09-28 18:40:56 -04:00
|
|
|
using namespace frc;
|
|
|
|
|
|
2019-11-02 13:35:03 -05:00
|
|
|
bool Trajectory::State::operator==(const Trajectory::State& other) const {
|
|
|
|
|
return t == other.t && velocity == other.velocity &&
|
|
|
|
|
acceleration == other.acceleration && pose == other.pose &&
|
|
|
|
|
curvature == other.curvature;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
bool Trajectory::State::operator!=(const Trajectory::State& other) const {
|
|
|
|
|
return !operator==(other);
|
|
|
|
|
}
|
|
|
|
|
|
2019-09-28 18:40:56 -04:00
|
|
|
Trajectory::State Trajectory::State::Interpolate(State endValue,
|
|
|
|
|
double i) const {
|
|
|
|
|
// Find the new [t] value.
|
|
|
|
|
const auto newT = Lerp(t, endValue.t, i);
|
|
|
|
|
|
|
|
|
|
// Find the delta time between the current state and the interpolated state.
|
|
|
|
|
const auto deltaT = newT - t;
|
|
|
|
|
|
|
|
|
|
// If delta time is negative, flip the order of interpolation.
|
2020-12-28 12:58:06 -08:00
|
|
|
if (deltaT < 0_s) {
|
|
|
|
|
return endValue.Interpolate(*this, 1.0 - i);
|
|
|
|
|
}
|
2019-09-28 18:40:56 -04:00
|
|
|
|
|
|
|
|
// Check whether the robot is reversing at this stage.
|
|
|
|
|
const auto reversing =
|
|
|
|
|
velocity < 0_mps ||
|
|
|
|
|
(units::math::abs(velocity) < 1E-9_mps && acceleration < 0_mps_sq);
|
|
|
|
|
|
|
|
|
|
// Calculate the new velocity.
|
|
|
|
|
// v = v_0 + at
|
|
|
|
|
const units::meters_per_second_t newV = velocity + (acceleration * deltaT);
|
|
|
|
|
|
|
|
|
|
// Calculate the change in position.
|
|
|
|
|
// delta_s = v_0 t + 0.5 at^2
|
|
|
|
|
const units::meter_t newS =
|
|
|
|
|
(velocity * deltaT + 0.5 * acceleration * deltaT * deltaT) *
|
|
|
|
|
(reversing ? -1.0 : 1.0);
|
|
|
|
|
|
|
|
|
|
// Return the new state. To find the new position for the new state, we need
|
|
|
|
|
// to interpolate between the two endpoint poses. The fraction for
|
|
|
|
|
// interpolation is the change in position (delta s) divided by the total
|
|
|
|
|
// distance between the two endpoints.
|
|
|
|
|
const double interpolationFrac =
|
|
|
|
|
newS / endValue.pose.Translation().Distance(pose.Translation());
|
|
|
|
|
|
|
|
|
|
return {newT, newV, acceleration,
|
|
|
|
|
Lerp(pose, endValue.pose, interpolationFrac),
|
|
|
|
|
Lerp(curvature, endValue.curvature, interpolationFrac)};
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
Trajectory::Trajectory(const std::vector<State>& states) : m_states(states) {
|
|
|
|
|
m_totalTime = states.back().t;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
Trajectory::State Trajectory::Sample(units::second_t t) const {
|
2020-12-28 12:58:06 -08:00
|
|
|
if (t <= m_states.front().t) {
|
|
|
|
|
return m_states.front();
|
|
|
|
|
}
|
|
|
|
|
if (t >= m_totalTime) {
|
|
|
|
|
return m_states.back();
|
|
|
|
|
}
|
2019-09-28 18:40:56 -04:00
|
|
|
|
2020-10-08 23:09:30 -04:00
|
|
|
// Use binary search to get the element with a timestamp no less than the
|
|
|
|
|
// requested timestamp. This starts at 1 because we use the previous state
|
|
|
|
|
// later on for interpolation.
|
|
|
|
|
auto sample =
|
|
|
|
|
std::lower_bound(m_states.cbegin() + 1, m_states.cend(), t,
|
|
|
|
|
[](const auto& a, const auto& b) { return a.t < b; });
|
2019-09-28 18:40:56 -04:00
|
|
|
|
2020-10-08 23:09:30 -04:00
|
|
|
auto prevSample = sample - 1;
|
2019-09-28 18:40:56 -04:00
|
|
|
|
|
|
|
|
// The sample's timestamp is now greater than or equal to the requested
|
|
|
|
|
// timestamp. If it is greater, we need to interpolate between the
|
|
|
|
|
// previous state and the current state to get the exact state that we
|
|
|
|
|
// want.
|
|
|
|
|
|
|
|
|
|
// If the difference in states is negligible, then we are spot on!
|
2020-10-08 23:09:30 -04:00
|
|
|
if (units::math::abs(sample->t - prevSample->t) < 1E-9_s) {
|
|
|
|
|
return *sample;
|
2019-09-28 18:40:56 -04:00
|
|
|
}
|
|
|
|
|
// Interpolate between the two states for the state that we want.
|
2020-10-08 23:09:30 -04:00
|
|
|
return prevSample->Interpolate(
|
|
|
|
|
*sample, (t - prevSample->t) / (sample->t - prevSample->t));
|
2019-09-28 18:40:56 -04:00
|
|
|
}
|
2019-11-02 13:35:03 -05:00
|
|
|
|
2019-12-23 14:16:30 -05:00
|
|
|
Trajectory Trajectory::TransformBy(const Transform2d& transform) {
|
|
|
|
|
auto& firstState = m_states[0];
|
|
|
|
|
auto& firstPose = firstState.pose;
|
|
|
|
|
|
|
|
|
|
// Calculate the transformed first pose.
|
|
|
|
|
auto newFirstPose = firstPose + transform;
|
|
|
|
|
auto newStates = m_states;
|
|
|
|
|
newStates[0].pose = newFirstPose;
|
|
|
|
|
|
|
|
|
|
for (unsigned int i = 1; i < newStates.size(); i++) {
|
|
|
|
|
auto& state = newStates[i];
|
|
|
|
|
// We are transforming relative to the coordinate frame of the new initial
|
|
|
|
|
// pose.
|
|
|
|
|
state.pose = newFirstPose + (state.pose - firstPose);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return Trajectory(newStates);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
Trajectory Trajectory::RelativeTo(const Pose2d& pose) {
|
|
|
|
|
auto newStates = m_states;
|
|
|
|
|
for (auto& state : newStates) {
|
|
|
|
|
state.pose = state.pose.RelativeTo(pose);
|
|
|
|
|
}
|
|
|
|
|
return Trajectory(newStates);
|
|
|
|
|
}
|
|
|
|
|
|
2021-02-16 21:06:36 -05:00
|
|
|
Trajectory Trajectory::operator+(const Trajectory& other) const {
|
|
|
|
|
// If this is a default constructed trajectory with no states, then we can
|
|
|
|
|
// simply return the rhs trajectory.
|
|
|
|
|
if (m_states.empty()) {
|
|
|
|
|
return other;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
auto states = m_states;
|
|
|
|
|
auto otherStates = other.States();
|
|
|
|
|
for (auto& otherState : otherStates) {
|
|
|
|
|
otherState.t += m_totalTime;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// Here we omit the first state of the other trajectory because we don't want
|
|
|
|
|
// two time points with different states. Sample() will automatically
|
|
|
|
|
// interpolate between the end of this trajectory and the second state of the
|
|
|
|
|
// other trajectory.
|
|
|
|
|
states.insert(states.end(), otherStates.begin() + 1, otherStates.end());
|
|
|
|
|
return Trajectory(states);
|
|
|
|
|
}
|
|
|
|
|
|
2019-11-02 13:35:03 -05:00
|
|
|
void frc::to_json(wpi::json& json, const Trajectory::State& state) {
|
|
|
|
|
json = wpi::json{{"time", state.t.to<double>()},
|
|
|
|
|
{"velocity", state.velocity.to<double>()},
|
|
|
|
|
{"acceleration", state.acceleration.to<double>()},
|
|
|
|
|
{"pose", state.pose},
|
|
|
|
|
{"curvature", state.curvature.to<double>()}};
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void frc::from_json(const wpi::json& json, Trajectory::State& state) {
|
|
|
|
|
state.pose = json.at("pose").get<Pose2d>();
|
|
|
|
|
state.t = units::second_t{json.at("time").get<double>()};
|
|
|
|
|
state.velocity =
|
|
|
|
|
units::meters_per_second_t{json.at("velocity").get<double>()};
|
|
|
|
|
state.acceleration =
|
|
|
|
|
units::meters_per_second_squared_t{json.at("acceleration").get<double>()};
|
2020-03-23 01:57:52 -04:00
|
|
|
state.curvature = units::curvature_t{json.at("curvature").get<double>()};
|
2019-11-02 13:35:03 -05:00
|
|
|
}
|
2020-05-28 06:43:32 +03:00
|
|
|
|
|
|
|
|
bool Trajectory::operator==(const Trajectory& other) const {
|
|
|
|
|
return m_states == other.States();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
bool Trajectory::operator!=(const Trajectory& other) const {
|
|
|
|
|
return !operator==(other);
|
|
|
|
|
}
|