format some more
This commit is contained in:
parent
a82f472559
commit
103333f9f0
|
@ -27,4 +27,4 @@ bool EpsilonEquals(const T& a, const T& b) {
|
||||||
return std::abs(a - b) < kEpsilon;
|
return std::abs(a - b) < kEpsilon;
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
|
@ -9,7 +9,6 @@ class RamseteTracker : public TrajectoryTracker {
|
||||||
|
|
||||||
TrajectoryTrackerVelocityOutput CalculateState(const TimedIterator<Pose2dWithCurvature>& iterator,
|
TrajectoryTrackerVelocityOutput CalculateState(const TimedIterator<Pose2dWithCurvature>& iterator,
|
||||||
const Pose2d& robot_pose) const override {
|
const Pose2d& robot_pose) const override {
|
||||||
|
|
||||||
const TimedEntry<Pose2dWithCurvature> reference_state = iterator.CurrentState().state;
|
const TimedEntry<Pose2dWithCurvature> reference_state = iterator.CurrentState().state;
|
||||||
const Pose2d error = reference_state.State().Pose().InFrameOfReferenceOf(robot_pose);
|
const Pose2d error = reference_state.State().Pose().InFrameOfReferenceOf(robot_pose);
|
||||||
|
|
||||||
|
@ -36,4 +35,4 @@ class RamseteTracker : public TrajectoryTracker {
|
||||||
double beta_;
|
double beta_;
|
||||||
double zeta_;
|
double zeta_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -63,4 +63,4 @@ class TrajectoryTracker {
|
||||||
std::unique_ptr<TrajectoryTrackerVelocityOutput> previous_velocity_;
|
std::unique_ptr<TrajectoryTrackerVelocityOutput> previous_velocity_;
|
||||||
double previous_time_ = -1.;
|
double previous_time_ = -1.;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,9 +1,9 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/Utilities.h"
|
|
||||||
#include "Rotation2d.h"
|
#include "Rotation2d.h"
|
||||||
#include "Translation2d.h"
|
#include "Translation2d.h"
|
||||||
#include "Twist2d.h"
|
#include "Twist2d.h"
|
||||||
|
#include "fl/Utilities.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
class Twist2d;
|
class Twist2d;
|
||||||
|
@ -103,4 +103,4 @@ class Pose2d final : public VaryInterpolatable<Pose2d> {
|
||||||
Translation2d translation_;
|
Translation2d translation_;
|
||||||
Rotation2d rotation_;
|
Rotation2d rotation_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -37,4 +37,4 @@ class Pose2dWithCurvature final : public VaryInterpolatable<Pose2dWithCurvature>
|
||||||
double curvature_;
|
double curvature_;
|
||||||
double dkds_;
|
double dkds_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -52,4 +52,4 @@ class Rotation2d final {
|
||||||
double cos_;
|
double cos_;
|
||||||
double sin_;
|
double sin_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -2,8 +2,8 @@
|
||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
|
||||||
#include "fl/types/VaryInterpolatable.h"
|
|
||||||
#include "Rotation2d.h"
|
#include "Rotation2d.h"
|
||||||
|
#include "fl/types/VaryInterpolatable.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
|
|
||||||
|
@ -58,4 +58,4 @@ class Translation2d final : public VaryInterpolatable<Translation2d> {
|
||||||
double x_;
|
double x_;
|
||||||
double y_;
|
double y_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -27,4 +27,4 @@ class Twist2d {
|
||||||
double dy_;
|
double dy_;
|
||||||
double dtheta_;
|
double dtheta_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -104,4 +104,4 @@ class ParametricQuinticHermiteSpline final : public ParametricSpline {
|
||||||
return radians;
|
return radians;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -17,4 +17,4 @@ class ParametricSpline {
|
||||||
private:
|
private:
|
||||||
Pose2d Pose(const double t) const { return Pose2d{Point(t), Heading(t)}; }
|
Pose2d Pose(const double t) const { return Pose2d{Point(t), Heading(t)}; }
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,10 +1,10 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <vector>
|
|
||||||
#include <memory>
|
#include <memory>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
|
||||||
#include "ParametricSpline.h"
|
#include "ParametricSpline.h"
|
||||||
|
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
constexpr static double kMinSampleSize = 1.;
|
constexpr static double kMinSampleSize = 1.;
|
||||||
|
@ -62,4 +62,4 @@ class SplineGenerator {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -66,4 +66,4 @@ class DistanceTrajectory : public Trajectory<double, S> {
|
||||||
std::vector<S> points_;
|
std::vector<S> points_;
|
||||||
std::shared_ptr<DistanceIterator<S>> iterator_;
|
std::shared_ptr<DistanceIterator<S>> iterator_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -65,4 +65,4 @@ class IndexedTrajectory : public Trajectory<double, S> {
|
||||||
std::shared_ptr<TrajectoryIterator<double, S>> iterator_;
|
std::shared_ptr<TrajectoryIterator<double, S>> iterator_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/types/VaryInterpolatable.h"
|
|
||||||
#include "TrajectoryIterator.h"
|
#include "TrajectoryIterator.h"
|
||||||
|
#include "fl/types/VaryInterpolatable.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
template <typename S>
|
template <typename S>
|
||||||
|
@ -97,4 +97,4 @@ class TimedTrajectory : public Trajectory<double, TimedEntry<S>> {
|
||||||
std::shared_ptr<TrajectoryIterator<double, TimedEntry<S>>> iterator_;
|
std::shared_ptr<TrajectoryIterator<double, TimedEntry<S>>> iterator_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -49,4 +49,4 @@ class Trajectory {
|
||||||
virtual S LastState() const = 0;
|
virtual S LastState() const = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
|
@ -2,13 +2,13 @@
|
||||||
|
|
||||||
#include <array>
|
#include <array>
|
||||||
|
|
||||||
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
|
||||||
#include "fl/mathematics/spline/ParametricQuinticHermiteSpline.h"
|
|
||||||
#include "fl/mathematics/spline/SplineGenerator.h"
|
|
||||||
#include "DistanceTrajectory.h"
|
#include "DistanceTrajectory.h"
|
||||||
#include "IndexedTrajectory.h"
|
#include "IndexedTrajectory.h"
|
||||||
#include "TimedTrajectory.h"
|
#include "TimedTrajectory.h"
|
||||||
#include "constraints/TimingConstraint.h"
|
#include "constraints/TimingConstraint.h"
|
||||||
|
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
||||||
|
#include "fl/mathematics/spline/ParametricQuinticHermiteSpline.h"
|
||||||
|
#include "fl/mathematics/spline/SplineGenerator.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
|
|
||||||
|
@ -256,4 +256,4 @@ class TrajectoryGenerator {
|
||||||
return TimedTrajectory<S>(timed_states, reversed);
|
return TimedTrajectory<S>(timed_states, reversed);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/Utilities.h"
|
|
||||||
#include "Trajectory.h"
|
#include "Trajectory.h"
|
||||||
|
#include "fl/Utilities.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
template <typename U, typename S>
|
template <typename U, typename S>
|
||||||
|
@ -40,4 +40,4 @@ class TrajectoryIterator {
|
||||||
U progress_;
|
U progress_;
|
||||||
TrajectorySamplePoint<S> sample_;
|
TrajectorySamplePoint<S> sample_;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
|
||||||
#include "TimingConstraint.h"
|
#include "TimingConstraint.h"
|
||||||
|
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
|
|
||||||
|
@ -62,4 +62,4 @@ class AngularAccelerationConstraint final : public TimingConstraint<Pose2dWithCu
|
||||||
double max_angular_acceleration_;
|
double max_angular_acceleration_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
|
||||||
#include "TimingConstraint.h"
|
#include "TimingConstraint.h"
|
||||||
|
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
|
|
||||||
|
@ -25,4 +25,4 @@ class CentripetalAccelerationConstraint final : public TimingConstraint<Pose2dWi
|
||||||
double max_centripetal_acceleration_;
|
double max_centripetal_acceleration_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -21,4 +21,4 @@ class TimingConstraint {
|
||||||
virtual double MaxVelocity(const S& state) const = 0;
|
virtual double MaxVelocity(const S& state) const = 0;
|
||||||
virtual MinMaxAcceleration MinMaxAcceleration(const S& state, double velocity) const = 0;
|
virtual MinMaxAcceleration MinMaxAcceleration(const S& state, double velocity) const = 0;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
|
||||||
#include "TimingConstraint.h"
|
#include "TimingConstraint.h"
|
||||||
|
#include "fl/mathematics/geometry/Pose2dWithCurvature.h"
|
||||||
|
|
||||||
namespace fl {
|
namespace fl {
|
||||||
|
|
||||||
|
@ -30,4 +30,4 @@ class VelocityLimitRadiusConstraint : public TimingConstraint<Pose2dWithCurvatur
|
||||||
double max_velocity_;
|
double max_velocity_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -13,4 +13,4 @@ class Interpolatable {
|
||||||
return start_value + (end_value - start_value) * Clamp(t, 0.0, 1.0);
|
return start_value + (end_value - start_value) * Clamp(t, 0.0, 1.0);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
|
@ -8,4 +8,4 @@ class VaryInterpolatable : public Interpolatable<T> {
|
||||||
public:
|
public:
|
||||||
virtual double Distance(const T& other) const = 0;
|
virtual double Distance(const T& other) const = 0;
|
||||||
};
|
};
|
||||||
} // namespace frc5190
|
} // namespace fl
|
||||||
|
|
Loading…
Reference in New Issue
Block a user