Autoware.Auto
autoware::prediction::Parameters Class Reference

#include <parameters.hpp>

Public Member Functions

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
 

Constructor & Destructor Documentation

◆ 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_steptime difference between two consecutive predicted states
time_horizontime difference from now into the future until which to predict objects

Member Function Documentation

◆ 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

getter for the time step


The documentation for this class was generated from the following files: