Autoware.Auto
autoware::common::motion_model::LinearMotionModel< StateT > Class Template Reference

A generic linear motion model class. More...

#include <linear_motion_model.hpp>

Inheritance diagram for autoware::common::motion_model::LinearMotionModel< StateT >:
Collaboration diagram for autoware::common::motion_model::LinearMotionModel< StateT >:

Public Types

using State = StateT
 

Protected Member Functions

State crtp_predict (const State &state, const std::chrono::nanoseconds &dt) const
 A crtp-called function that predicts the state forward. More...
 
State::Matrix crtp_jacobian (const State &, const std::chrono::nanoseconds &dt) const
 A crtp-called function that computes a Jacobian. More...
 
- Protected Member Functions inherited from autoware::common::helper_functions::crtp< LinearMotionModel< StateT > >
const LinearMotionModel< StateT > & impl () const
 
LinearMotionModel< StateT > & impl ()
 

Protected Attributes

friend MotionModelInterface< LinearMotionModel< StateT > >
 

Additional Inherited Members

- Public Member Functions inherited from autoware::common::motion_model::MotionModelInterface< LinearMotionModel< StateT > >
auto predict (const StateT &state, const std::chrono::nanoseconds &dt) const
 Get the next predicted state. More...
 
auto jacobian (const StateT &state, const std::chrono::nanoseconds &dt) const
 Get the Jacobian of this motion model. More...
 

Detailed Description

template<typename StateT>
class autoware::common::motion_model::LinearMotionModel< StateT >

A generic linear motion model class.

This class is designed to handle all the linear motion models, i.e., those that only have independent variables in them. In this case, the Jacobian is just a transition matrix.

Template Parameters
StateTState type.

Member Typedef Documentation

◆ State

template<typename StateT >
using autoware::common::motion_model::LinearMotionModel< StateT >::State = StateT

Member Function Documentation

◆ crtp_jacobian()

template<typename StateT >
StateT::Matrix autoware::common::motion_model::LinearMotionModel< StateT >::crtp_jacobian ( const State ,
const std::chrono::nanoseconds &  dt 
) const
protected

A crtp-called function that computes a Jacobian.

Note
The default implementation assumes that all variables have position, velocity and acceleration entries. If a custom state that does not follow this convention is to be used a specialization of this function must be added.
Returns
A matrix that represents the Jacobian.

◆ crtp_predict()

template<typename StateT >
State autoware::common::motion_model::LinearMotionModel< StateT >::crtp_predict ( const State state,
const std::chrono::nanoseconds &  dt 
) const
inlineprotected

A crtp-called function that predicts the state forward.

Parameters
[in]stateThe current state vector
[in]dtTime difference
Returns
New state after prediction.

Member Data Documentation

◆ MotionModelInterface< LinearMotionModel< StateT > >

template<typename StateT >
friend autoware::common::motion_model::LinearMotionModel< StateT >::MotionModelInterface< LinearMotionModel< StateT > >
protected

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