|
MOTION_TESTING_PUBLIC State | motion::motion_testing::make_state (Real x0, Real y0, Real heading, Real v0, Real a0, Real turn_rate, std::chrono::system_clock::time_point t) |
| Makes a state, intended to make message generation more terse. More...
|
|
MOTION_TESTING_PUBLIC State | motion::motion_testing::generate_state (Generator &gen) |
| Generates a state from a normal distribution with the following bounds: TODO(c.ho) More...
|
|
MOTION_TESTING_PUBLIC Trajectory | motion::motion_testing::generate_trajectory (const State &start_state, Generator &gen) |
| Generates a trajectory assuming the starting state, a bicycle model, and additive noise applied to XXX Note: not implemented. More...
|
|
MOTION_TESTING_PUBLIC Trajectory | motion::motion_testing::constant_trajectory (const State &start_state, std::chrono::nanoseconds dt) |
| Generate a trajectory given the start state, assuming the highest derivatives are held constant. Note: heading_rate behavior will be kind of off TODO(c.ho) Note: lateral_velocity_mps will not be respected TODO(cho) More...
|
|
MOTION_TESTING_PUBLIC Trajectory | motion::motion_testing::bad_heading_trajectory (const State &start_state, std::chrono::nanoseconds dt) |
| Generates a constant velocity trajectory. More...
|
|
Trajectory | motion::motion_testing::constant_velocity_trajectory (const Real x0, const Real y0, const Real heading, const Real v0, const std::chrono::nanoseconds dt) |
|
Trajectory | motion::motion_testing::constant_acceleration_trajectory (const Real x0, const Real y0, const Real heading, const Real v0, const Real a0, const std::chrono::nanoseconds dt) |
|
Trajectory | motion::motion_testing::constant_velocity_turn_rate_trajectory (const Real x0, const Real y0, const Real heading, const Real v0, const Real turn_rate, const std::chrono::nanoseconds dt) |
|
Trajectory | motion::motion_testing::constant_acceleration_turn_rate_trajectory (const Real x0, const Real y0, const Real heading, const Real v0, const Real a0, const Real turn_rate, const std::chrono::nanoseconds dt) |
|
MOTION_TESTING_PUBLIC void | motion::motion_testing::next_state (const Trajectory &trajectory, State &state, uint32_t hint, Generator *gen=nullptr) |
|
MOTION_TESTING_PUBLIC Index | motion::motion_testing::progresses_towards_target (const Trajectory &trajectory, const Point &target, Real heading_tolerance=Real{0.006F}) |
|
MOTION_TESTING_PUBLIC Index | motion::motion_testing::dynamically_feasible (const Trajectory &trajectory, Real tolerance=0.05F) |
|