#include <parameters.hpp>
|
LONELY_WORLD_PREDICTION_PUBLIC | Parameters (std::chrono::microseconds time_step, std::chrono::microseconds time_horizon) |
|
std::chrono::microseconds LONELY_WORLD_PREDICTION_PUBLIC | time_step () const noexcept |
|
std::chrono::microseconds LONELY_WORLD_PREDICTION_PUBLIC | time_horizon () const noexcept |
|
◆ Parameters()
autoware::prediction::Parameters::Parameters |
( |
std::chrono::microseconds |
time_step, |
|
|
std::chrono::microseconds |
time_horizon |
|
) |
| |
parameters for lonely-world prediction
Enforced constraints:
- step > 0
- horizon > 0
- horizon >= step
- Exceptions
-
<tt>std::invalid_argument</tt> | if constraints are not satisfied |
- Parameters
-
time_step | time difference between two consecutive predicted states |
time_horizon | time difference from now into the future until which to predict objects |
◆ time_horizon()
std::chrono::microseconds LONELY_WORLD_PREDICTION_PUBLIC autoware::prediction::Parameters::time_horizon |
( |
| ) |
const |
|
inlinenoexcept |
getter for the time horizon
◆ time_step()
std::chrono::microseconds LONELY_WORLD_PREDICTION_PUBLIC autoware::prediction::Parameters::time_step |
( |
| ) |
const |
|
inlinenoexcept |
The documentation for this class was generated from the following files: