Autoware.Auto
autoware::motion::control::trajectory_follower::DebugValues Class Reference

Debug Values used for debugging or controller tuning. More...

#include <debug_values.hpp>

Public Types

enum  TYPE {
  TYPE::DT = 0, TYPE::CURRENT_VEL = 1, TYPE::TARGET_VEL = 2, TYPE::TARGET_ACC = 3,
  TYPE::NEAREST_VEL = 4, TYPE::NEAREST_ACC = 5, TYPE::SHIFT = 6, TYPE::PITCH_LPF_RAD = 7,
  TYPE::PITCH_RAW_RAD = 8, TYPE::PITCH_LPF_DEG = 9, TYPE::PITCH_RAW_DEG = 10, TYPE::ERROR_VEL = 11,
  TYPE::ERROR_VEL_FILTERED = 12, TYPE::CONTROL_STATE = 13, TYPE::ACC_CMD_PID_APPLIED = 14, TYPE::ACC_CMD_ACC_LIMITED = 15,
  TYPE::ACC_CMD_JERK_LIMITED = 16, TYPE::ACC_CMD_SLOPE_APPLIED = 17, TYPE::ACC_CMD_PUBLISHED = 18, TYPE::ACC_CMD_FB_P_CONTRIBUTION = 19,
  TYPE::ACC_CMD_FB_I_CONTRIBUTION = 20, TYPE::ACC_CMD_FB_D_CONTRIBUTION = 21, TYPE::FLAG_STOPPING = 22, TYPE::FLAG_EMERGENCY_STOP = 23,
  TYPE::PREDICTED_VEL = 24, TYPE::CALCULATED_ACC = 25, TYPE::PITCH_RAW_TRAJ_RAD = 26, TYPE::PITCH_RAW_TRAJ_DEG = 27,
  TYPE::STOP_DIST = 28, TYPE::SIZE
}
 Types of debug values. More...
 

Public Member Functions

size_t getValuesIdx (const TYPE type) const
 get the index corresponding to the given value TYPE More...
 
std::array< float64_t, static_cast< size_t >TYPE::SIZE)> getValues () const
 get all the debug values as an std::array More...
 
void setValues (const TYPE type, const float64_t value)
 set the given type to the given value More...
 
void setValues (const size_t type, const float64_t value)
 set the given type to the given value More...
 

Detailed Description

Debug Values used for debugging or controller tuning.

Member Enumeration Documentation

◆ TYPE

Types of debug values.

Enumerator
DT 
CURRENT_VEL 
TARGET_VEL 
TARGET_ACC 
NEAREST_VEL 
NEAREST_ACC 
SHIFT 
PITCH_LPF_RAD 
PITCH_RAW_RAD 
PITCH_LPF_DEG 
PITCH_RAW_DEG 
ERROR_VEL 
ERROR_VEL_FILTERED 
CONTROL_STATE 
ACC_CMD_PID_APPLIED 
ACC_CMD_ACC_LIMITED 
ACC_CMD_JERK_LIMITED 
ACC_CMD_SLOPE_APPLIED 
ACC_CMD_PUBLISHED 
ACC_CMD_FB_P_CONTRIBUTION 
ACC_CMD_FB_I_CONTRIBUTION 
ACC_CMD_FB_D_CONTRIBUTION 
FLAG_STOPPING 
FLAG_EMERGENCY_STOP 
PREDICTED_VEL 
CALCULATED_ACC 
PITCH_RAW_TRAJ_RAD 
PITCH_RAW_TRAJ_DEG 
STOP_DIST 
SIZE 

Member Function Documentation

◆ getValues()

std::array<float64_t, static_cast<size_t>TYPE::SIZE)> autoware::motion::control::trajectory_follower::DebugValues::getValues ( ) const
inline

get all the debug values as an std::array

Returns
array of all debug values

◆ getValuesIdx()

size_t autoware::motion::control::trajectory_follower::DebugValues::getValuesIdx ( const TYPE  type) const
inline

get the index corresponding to the given value TYPE

Parameters
[in]typethe TYPE enum for which to get the index
Returns
index of the type

◆ setValues() [1/2]

void autoware::motion::control::trajectory_follower::DebugValues::setValues ( const size_t  type,
const float64_t  value 
)
inline

set the given type to the given value

Parameters
[in]typeindex of the type
[in]valuevalue to set

◆ setValues() [2/2]

void autoware::motion::control::trajectory_follower::DebugValues::setValues ( const TYPE  type,
const float64_t  value 
)
inline

set the given type to the given value

Parameters
[in]typeTYPE of the value
[in]valuevalue to set

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