Autoware.Auto
debug_values.hpp
Go to the documentation of this file.
1 // Copyright 2021 Tier IV, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAJECTORY_FOLLOWER__DEBUG_VALUES_HPP_
16 #define TRAJECTORY_FOLLOWER__DEBUG_VALUES_HPP_
17 
18 #include <array>
19 
20 #include "common/types.hpp"
22 
23 namespace autoware
24 {
25 namespace motion
26 {
27 namespace control
28 {
30 {
33 class TRAJECTORY_FOLLOWER_PUBLIC DebugValues
34 {
35 public:
37  enum class TYPE
38  {
39  DT = 0,
40  CURRENT_VEL = 1,
41  TARGET_VEL = 2,
42  TARGET_ACC = 3,
43  NEAREST_VEL = 4,
44  NEAREST_ACC = 5,
45  SHIFT = 6,
46  PITCH_LPF_RAD = 7,
47  PITCH_RAW_RAD = 8,
48  PITCH_LPF_DEG = 9,
49  PITCH_RAW_DEG = 10,
50  ERROR_VEL = 11,
51  ERROR_VEL_FILTERED = 12,
52  CONTROL_STATE = 13,
53  ACC_CMD_PID_APPLIED = 14,
54  ACC_CMD_ACC_LIMITED = 15,
55  ACC_CMD_JERK_LIMITED = 16,
56  ACC_CMD_SLOPE_APPLIED = 17,
57  ACC_CMD_PUBLISHED = 18,
58  ACC_CMD_FB_P_CONTRIBUTION = 19,
59  ACC_CMD_FB_I_CONTRIBUTION = 20,
60  ACC_CMD_FB_D_CONTRIBUTION = 21,
61  FLAG_STOPPING = 22,
62  FLAG_EMERGENCY_STOP = 23,
63  PREDICTED_VEL = 24,
64  CALCULATED_ACC = 25,
65  PITCH_RAW_TRAJ_RAD = 26,
66  PITCH_RAW_TRAJ_DEG = 27,
67  STOP_DIST = 28,
68  SIZE // this is the number of enum elements
69  };
70 
76  size_t getValuesIdx(const TYPE type) const {return static_cast<size_t>(type);}
81  std::array<float64_t, static_cast<size_t>(TYPE::SIZE)> getValues() const {return m_values;}
87  void setValues(const TYPE type, const float64_t value)
88  {
89  m_values.at(static_cast<size_t>(type)) = value;
90  }
96  void setValues(const size_t type, const float64_t value) {m_values.at(type) = value;}
97 
98 private:
99  std::array<float64_t, static_cast<size_t>(TYPE::SIZE)> m_values;
100 };
101 } // namespace trajectory_follower
102 } // namespace control
103 } // namespace motion
104 } // namespace autoware
105 
106 #endif // TRAJECTORY_FOLLOWER__DEBUG_VALUES_HPP_
autoware::motion::control::trajectory_follower::DebugValues::setValues
void setValues(const TYPE type, const float64_t value)
set the given type to the given value
Definition: debug_values.hpp:87
visibility_control.hpp
types.hpp
This file includes common type definition.
autoware::motion::control::trajectory_follower::DebugValues::TYPE
TYPE
Types of debug values.
Definition: debug_values.hpp:37
autoware::motion::control::trajectory_follower::DebugValues::getValues
std::array< float64_t, static_cast< size_t >TYPE::SIZE)> getValues() const
get all the debug values as an std::array
Definition: debug_values.hpp:81
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::control::trajectory_follower::DebugValues::getValuesIdx
size_t getValuesIdx(const TYPE type) const
get the index corresponding to the given value TYPE
Definition: debug_values.hpp:76
autoware::motion::control::trajectory_follower::DebugValues::setValues
void setValues(const size_t type, const float64_t value)
set the given type to the given value
Definition: debug_values.hpp:96
autoware::motion::control::trajectory_follower
Definition: debug_values.hpp:29
motion
Definition: controller_base.hpp:31
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::motion::control::trajectory_follower::DebugValues
Debug Values used for debugging or controller tuning.
Definition: debug_values.hpp:33