Autoware.Auto
safety_state_machine.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
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 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
18 #ifndef VEHICLE_INTERFACE__SAFETY_STATE_MACHINE_HPP_
19 #define VEHICLE_INTERFACE__SAFETY_STATE_MACHINE_HPP_
20 
21 #include <common/types.hpp>
22 #include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
23 #include <autoware_auto_msgs/msg/vehicle_odometry.hpp>
24 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp>
25 #include <autoware_auto_msgs/msg/vehicle_state_report.hpp>
26 #include <vehicle_interface/visibility_control.hpp>
27 
28 #include <experimental/optional>
29 #include <algorithm>
30 #include <chrono>
31 #include <vector>
32 
34 
35 namespace autoware
36 {
37 namespace drivers
38 {
39 namespace vehicle_interface
40 {
41 using MaybeStateCommand = std::experimental::optional<autoware_auto_msgs::msg::VehicleStateCommand>;
43 using Odometry = autoware_auto_msgs::msg::VehicleOdometry;
44 using StateReport = autoware_auto_msgs::msg::VehicleStateReport;
47 {
48 public:
51  const BasicControlCommand & control = BasicControlCommand{},
52  const MaybeStateCommand & state = MaybeStateCommand{})
53  : m_control{control}, m_state{state} {}
54 
56  const BasicControlCommand & control() const noexcept {return m_control;}
58  const MaybeStateCommand & state() const noexcept {return m_state;}
59 
60 private:
61  BasicControlCommand m_control;
62  MaybeStateCommand m_state;
63 }; // class Command
64 
67 enum class StateMachineReport : uint8_t
68 {
70  BAD_STATE,
78 }; // enum class StateMachineWarning
79 
80 // TODO(c.ho) concept comparable
83 template<typename T>
85 {
86 public:
89  Limits(T min, T max, T threshold)
90  : m_min{min}, m_max{max}, m_threshold{threshold}
91  {
92  if (min >= max) {
93  throw std::domain_error{"min >= max"};
94  }
95  }
96 
97  T min() const noexcept {return m_min;}
98  T max() const noexcept {return m_max;}
99  T threshold() const noexcept {return m_threshold;}
101  bool8_t clamp_warn(T & value) const noexcept
102  {
103  const auto value_raw = value;
104  value = std::min(std::max(m_min, value_raw), m_max);
105  return std::abs(value - value_raw) >= m_threshold;
106  }
107 
108 private:
109  T m_min;
110  T m_max;
111  T m_threshold;
112 };
113 
116 {
117 public:
118  using VelocityT = decltype(Odometry::velocity_mps);
119  using AccelT = decltype(BasicControlCommand::long_accel_mps2);
121  using FrontWheelLimits = Limits<decltype(BasicControlCommand::front_wheel_angle_rad)>;
122 
143  const VelocityT gear_shift_velocity_threshold,
144  const AccelLimits & accel_limits,
145  const FrontWheelLimits & front_wheel_limits,
146  const std::chrono::nanoseconds time_step,
147  const AccelT timeout_accel_mps2,
148  const std::chrono::nanoseconds state_transition_timeout,
149  const AccelT auto_gear_shift_accel_deadzone_mps2
150  );
151 
152  VelocityT gear_shift_velocity_threshold() const noexcept;
153  const AccelLimits & accel_limits() const noexcept;
154  const FrontWheelLimits & front_wheel_limits() const noexcept;
155  std::chrono::nanoseconds time_step() const noexcept;
156  AccelT timeout_acceleration() const noexcept;
157  std::chrono::nanoseconds state_transition_timeout() const noexcept;
158  AccelT auto_gear_shift_accel_deadzone() const noexcept;
159 
160 private:
161  VelocityT m_gear_shift_velocity_threshold;
162  AccelLimits m_accel_limits;
163  FrontWheelLimits m_front_wheel_limits;
164  std::chrono::nanoseconds m_time_step;
165  AccelT m_timeout_acceleration;
166  std::chrono::nanoseconds m_state_transition_timeout;
167  AccelT m_auto_gear_shift_accel_deadzone;
168 }; // class StateMachineConfig
169 
174 {
175 public:
176  using Reports = std::vector<StateMachineReport>; // TODO(c.ho) maybe a set instead
178  explicit SafetyStateMachine(const StateMachineConfig & config);
183  Command compute_safe_commands(const Command & command);
187  void update(const Odometry & odom, const StateReport & state);
190  Command timeout_commands() const noexcept;
192  const Reports & reports() const noexcept;
194  const StateMachineConfig & get_config() const noexcept;
195 
196 private:
197  using VSC = autoware_auto_msgs::msg::VehicleStateCommand;
198  using MaybeEnum = std::experimental::optional<decltype(VSC::blinker)>;
199  //lint -save -e9150 NOLINT Pure aggregate and only used internally; no constraints on state
200  template<typename T>
201  struct ValueStamp
202  {
203  T value;
204  std::chrono::system_clock::time_point stamp{std::chrono::system_clock::time_point::min()};
205  };
206  struct StateChangeRequests
207  {
208  ValueStamp<decltype(VSC::gear)> gear;
209  ValueStamp<decltype(VSC::blinker)> blinker;
210  ValueStamp<decltype(VSC::wiper)> wiper;
211  ValueStamp<decltype(VSC::headlight)> headlight;
212  ValueStamp<decltype(VSC::mode)> mode;
213  ValueStamp<decltype(VSC::hand_brake)> hand_brake;
214  ValueStamp<decltype(VSC::horn)> horn;
215  }; // struct StateChangeRequest
216  //lint -restore NOLINT
217  // Make sure uint members are within range--otherwise set to NO_COMMAND
218  VEHICLE_INTERFACE_LOCAL VSC sanitize(const VSC & msg) const;
219  // Turn on headlights if the wipers are being turned on
220  VEHICLE_INTERFACE_LOCAL static MaybeEnum headlights_on_if_wipers_on(const VSC & in);
221  // Apply gear shift if velocity is small and commanded acceleration is big enough
222  VEHICLE_INTERFACE_LOCAL uint8_t automatic_gear_shift(
223  const BasicControlCommand control,
224  const VSC & state) const;
225  // Remove "big" gear shifts if velocity is too large in magnitude
226  VEHICLE_INTERFACE_LOCAL bool8_t bad_gear_shift(const VSC & in) const;
227  // Clamp control values; warn if wildly out of range
229  // Add/overwrite any new state change requests
230  VEHICLE_INTERFACE_LOCAL void cache_state_change_request(const VSC & in);
231  // Clear any state changes that have happened, or warn on timeout
232  VEHICLE_INTERFACE_LOCAL void check_state_change(const StateReport & in);
233 
234  StateMachineConfig m_config;
235  Odometry m_odometry{};
236  StateReport m_state{};
237  StateChangeRequests m_requests{};
238  mutable Reports m_reports{};
239 }; // class SafetyStateMachine
240 } // namespace vehicle_interface
241 } // namespace drivers
242 } // namespace autoware
243 
244 #endif // VEHICLE_INTERFACE__SAFETY_STATE_MACHINE_HPP_
autoware::motion::control::pure_pursuit::VehicleControlCommand
autoware_auto_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
autoware::drivers::vehicle_interface::StateMachineReport::STATE_TRANSITION_TIMEOUT
@ STATE_TRANSITION_TIMEOUT
Commanded state transition didn't happen.
catr_diff.T
T
Definition: catr_diff.py:22
autoware::drivers::vehicle_interface::Limits::threshold
T threshold() const noexcept
Definition: safety_state_machine.hpp:99
types.hpp
This file includes common type definition.
autoware::drivers::vehicle_interface::StateMachineReport
StateMachineReport
Definition: safety_state_machine.hpp:67
motion::motion_common::clamp
T clamp(T val, T min, T max)
Standard clamp implementation.
Definition: motion_common.hpp:142
autoware::drivers::vehicle_interface::StateReport
autoware_auto_msgs::msg::VehicleStateReport StateReport
Definition: safety_state_machine.hpp:44
autoware::drivers::vehicle_interface::Command::Command
Command(const BasicControlCommand &control=BasicControlCommand{}, const MaybeStateCommand &state=MaybeStateCommand{})
Constructor.
Definition: safety_state_machine.hpp:50
autoware::drivers::vehicle_interface::Limits::min
T min() const noexcept
Definition: safety_state_machine.hpp:97
autoware::drivers::vehicle_interface::StateMachineConfig
Configuration class for SafetyStateMachine.
Definition: safety_state_machine.hpp:115
autoware::drivers::vehicle_interface::StateMachineReport::BAD_STATE
@ BAD_STATE
A state command was not one of the specified constants.
autoware::drivers::vehicle_interface::StateMachineReport::CLAMP_PAST_THRESHOLD
@ CLAMP_PAST_THRESHOLD
Clamped a command that was way out of bounds.
autoware::drivers::vehicle_interface::MaybeStateCommand
std::experimental::optional< autoware_auto_msgs::msg::VehicleStateCommand > MaybeStateCommand
Definition: safety_state_machine.hpp:41
autoware::drivers::vehicle_interface::Command::control
const BasicControlCommand & control() const noexcept
Getter.
Definition: safety_state_machine.hpp:56
autoware_auto_msgs
Definition: motion_common.hpp:255
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware::drivers::vehicle_interface::SafetyStateMachine
Definition: safety_state_machine.hpp:173
autoware::drivers::vehicle_interface::Limits::clamp_warn
bool8_t clamp_warn(T &value) const noexcept
Clamps value to max/min range; return true if value is threshold past limits.
Definition: safety_state_machine.hpp:101
autoware::drivers::vehicle_interface::Odometry
autoware_auto_msgs::msg::VehicleOdometry Odometry
Definition: safety_state_machine.hpp:43
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
VEHICLE_INTERFACE_LOCAL
#define VEHICLE_INTERFACE_LOCAL
Definition: drivers/vehicle_interface/include/vehicle_interface/visibility_control.hpp:45
autoware::drivers::vehicle_interface::Limits
Definition: safety_state_machine.hpp:84
autoware::drivers::vehicle_interface::Limits::Limits
Limits(T min, T max, T threshold)
Definition: safety_state_machine.hpp:89
autoware::drivers::vehicle_interface::Command::state
const MaybeStateCommand & state() const noexcept
Getter.
Definition: safety_state_machine.hpp:58
autoware::drivers::vehicle_interface::StateMachineReport::WIPERS_ON_HEADLIGHTS_ON
@ WIPERS_ON_HEADLIGHTS_ON
Turn on headlights because you turned on wipers.
autoware::drivers::vehicle_interface::StateMachineReport::HIGH_FREQUENCY_STEER_REPORT
@ HIGH_FREQUENCY_STEER_REPORT
Reported steering has high frequency components.
autoware::drivers::vehicle_interface::StateMachineReport::HIGH_FREQUENCY_VELOCITY_REPORT
@ HIGH_FREQUENCY_VELOCITY_REPORT
Reported velocity has high frequency components.
autoware::drivers::vehicle_interface::StateMachineReport::REMOVE_GEAR_COMMAND
@ REMOVE_GEAR_COMMAND
Converted gear command to GEAR_NO_COMMAND because you're going too fast.
autoware::drivers::vehicle_interface::StateMachineConfig::AccelT
decltype(BasicControlCommand::long_accel_mps2) AccelT
Definition: safety_state_machine.hpp:119
autoware::drivers::vehicle_interface::BasicControlCommand
autoware_auto_msgs::msg::VehicleControlCommand BasicControlCommand
Definition: safety_state_machine.hpp:42
autoware::drivers::vehicle_interface::StateMachineReport::HIGH_FREQUENCY_ACCELERATION_COMMAND
@ HIGH_FREQUENCY_ACCELERATION_COMMAND
Acceleration has high frequency components.
autoware::drivers::vehicle_interface::StateMachineReport::HIGH_FREQUENCY_STEER_COMMAND
@ HIGH_FREQUENCY_STEER_COMMAND
Steering has high frequency components.
autoware::drivers::vehicle_interface::StateMachineConfig::VelocityT
decltype(Odometry::velocity_mps) VelocityT
Definition: safety_state_machine.hpp:118
autoware::drivers::vehicle_interface::SafetyStateMachine::Reports
std::vector< StateMachineReport > Reports
Definition: safety_state_machine.hpp:176
autoware::drivers::vehicle_interface::Command
Simple wrapper for control command and state command together.
Definition: safety_state_machine.hpp:46
lgsvl_interface::VSC
autoware_auto_msgs::msg::VehicleStateCommand VSC
Definition: lgsvl_interface.hpp:78
autoware::drivers::vehicle_interface::Limits::max
T max() const noexcept
Definition: safety_state_machine.hpp:98
VEHICLE_INTERFACE_PUBLIC
#define VEHICLE_INTERFACE_PUBLIC
Definition: drivers/vehicle_interface/include/vehicle_interface/visibility_control.hpp:44