Autoware.Auto
controller_base.hpp
Go to the documentation of this file.
1 // Copyright 2019 Christopher Ho
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 #ifndef CONTROLLER_COMMON__CONTROLLER_BASE_HPP_
15 #define CONTROLLER_COMMON__CONTROLLER_BASE_HPP_
16 
20 
21 #include <chrono>
22 #include <string>
23 
24 #define CONTROLLER_COMMON_COPY_MOVE_ASSIGNABLE(Class) \
25  Class(const Class &) = default; \
26  Class(Class &&) = default; \
27  Class & operator=(const Class &) = default; \
28  Class & operator=(Class &&) = default; \
29  ~Class() = default;
30 
31 namespace motion
32 {
33 namespace control
34 {
35 namespace controller_common
36 {
37 
45 
46 enum class ControlReference
47 {
48  TEMPORAL,
49  SPATIAL
50 }; // enum class ControlReference
51 
53 class CONTROLLER_COMMON_PUBLIC BehaviorConfig
54 {
55 public:
58  Real safe_deceleration_rate_mps2,
59  std::chrono::nanoseconds time_step,
60  ControlReference type);
62 
63  Real safe_deceleration_rate() const noexcept;
64  std::chrono::nanoseconds time_step() const noexcept;
65  bool is_spatial_reference() const noexcept;
66  bool is_temporal_reference() const noexcept;
67 
68 private:
69  Real m_safe_deceleration_rate_mps2;
70  std::chrono::nanoseconds m_time_step;
71  bool m_is_spatial_reference;
72 }; // class BehaviorConfig
73 
76 class CONTROLLER_COMMON_PUBLIC ControllerBase
77 {
78 public:
80  explicit ControllerBase(const BehaviorConfig & config);
81  ControllerBase(const ControllerBase &) = default;
82  ControllerBase(ControllerBase &&) = default;
83  ControllerBase & operator=(const ControllerBase &) = default;
84  ControllerBase & operator=(ControllerBase &&) = default;
85  virtual ~ControllerBase() noexcept = default;
86 
89  void set_trajectory(const Trajectory & trajectory);
91  const Trajectory & get_reference_trajectory() const noexcept;
92 
96  Command compute_command(const State & state);
97 
99  Command compute_stop_command(const State & state) const noexcept;
100 
105  Index get_current_state_spatial_index() const;
110  Index get_current_state_temporal_index() const;
111 
113  virtual std::string name() const;
114 
116  virtual Index get_compute_iterations() const;
117 
118  const BehaviorConfig & get_base_config() const noexcept;
119 
120 protected:
123  virtual bool check_new_trajectory(const Trajectory & trajectory) const;
126  virtual const Trajectory & handle_new_trajectory(const Trajectory & trajectory);
128  virtual Command compute_command_impl(const State & state) = 0;
130  Point predict(const Point & point, std::chrono::nanoseconds dt) noexcept;
132  void set_base_config(const BehaviorConfig & config) noexcept;
133 
134 private:
136  CONTROLLER_COMMON_LOCAL bool is_state_ok(const State & state) const noexcept;
138  CONTROLLER_COMMON_LOCAL void update_reference_indices(const State & new_state) noexcept;
140  CONTROLLER_COMMON_LOCAL bool is_past_trajectory(const State & state) const noexcept;
142  CONTROLLER_COMMON_LOCAL void set_trajectory_impl();
143 
144  BehaviorConfig m_config;
145  Trajectory m_reference_trajectory;
146  std::chrono::system_clock::time_point m_latest_reference;
147  Index m_reference_spatial_index;
148  Index m_reference_temporal_index;
150 }; // class ControllerBase
151 
153 CONTROLLER_COMMON_PUBLIC void compute_diagnostic(
154  const ControllerBase & ctrl,
155  const State & state,
156  bool use_temporal_reference, // TODO(c.ho) kind of a bad interface
157  Diagnostic & out);
158 
159 } // namespace controller_common
160 } // namespace control
161 } // namespace motion
162 #endif // CONTROLLER_COMMON__CONTROLLER_BASE_HPP_
motion::control::controller_common::compute_diagnostic
CONTROLLER_COMMON_PUBLIC void compute_diagnostic(const ControllerBase &ctrl, const State &state, bool use_temporal_reference, Diagnostic &out)
Fill out a controller diagnostic message.
Definition: controller_base.cpp:287
motion::motion_common::Real
decltype(autoware_auto_planning_msgs::msg::TrajectoryPoint::longitudinal_velocity_mps) Real
Definition: motion_common.hpp:37
motion::control::controller_common::ControlReference::TEMPORAL
@ TEMPORAL
CONTROLLER_COMMON_COPY_MOVE_ASSIGNABLE
#define CONTROLLER_COMMON_COPY_MOVE_ASSIGNABLE(Class)
Definition: controller_base.hpp:24
visibility_control.hpp
motion::motion_common::Command
autoware_auto_vehicle_msgs::msg::VehicleControlCommand Command
Definition: motion_common.hpp:38
motion::control::controller_common::ControlReference
ControlReference
Definition: controller_base.hpp:46
motion::motion_common::State
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:40
setup.name
name
Definition: setup.py:6
motion::motion_common::Point
decltype(Trajectory::points)::value_type Point
Definition: motion_common.hpp:45
motion::motion_common::Diagnostic
autoware_auto_system_msgs::msg::ControlDiagnostic Diagnostic
Definition: motion_common.hpp:39
motion_common.hpp
motion::motion_common::Index
decltype(Trajectory::points)::size_type Index
Definition: motion_common.hpp:44
motion::control::controller_common::ControlReference::SPATIAL
@ SPATIAL
motion::control::controller_common::ControllerBase
Definition: controller_base.hpp:76
differential_drive_motion_model.hpp
motion
Definition: controller_base.hpp:31
motion::control::controller_common::BehaviorConfig
Specifies the behavior of the controller.
Definition: controller_base.hpp:53
motion::motion_common::Trajectory
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
Point
geometry_msgs::msg::Point32 Point
Definition: cluster2d.cpp:28
autoware::common::motion_model::DifferentialDriveMotionModel
A generic differential motion model. This class only exists to be specialized for specific motion mod...
Definition: differential_drive_motion_model.hpp:35
autoware::common::geometry::spatial_hash::Index
std::size_t Index
Index type for identifying bins of the hash/lattice.
Definition: spatial_hash_config.hpp:49