Autoware.Auto
ssc_interface.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 
18 
19 #ifndef SSC_INTERFACE__SSC_INTERFACE_HPP_
20 #define SSC_INTERFACE__SSC_INTERFACE_HPP_
21 
23 
24 #include <common/types.hpp>
27 
28 #include <automotive_platform_msgs/msg/gear_command.hpp>
29 #include <automotive_platform_msgs/msg/gear_feedback.hpp>
30 #include <automotive_platform_msgs/msg/speed_mode.hpp>
31 #include <automotive_platform_msgs/msg/steering_feedback.hpp>
32 #include <automotive_platform_msgs/msg/steer_mode.hpp>
33 #include <automotive_platform_msgs/msg/turn_signal_command.hpp>
34 #include <automotive_platform_msgs/msg/velocity_accel_cov.hpp>
35 #include <autoware_auto_msgs/msg/high_level_control_command.hpp>
36 #include <autoware_auto_msgs/msg/raw_control_command.hpp>
37 #include <autoware_auto_msgs/msg/trajectory_point.hpp>
38 #include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
39 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
40 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp>
41 #include <autoware_auto_msgs/msg/vehicle_state_report.hpp>
42 #include <autoware_auto_msgs/srv/autonomy_mode_change.hpp>
43 #include <std_msgs/msg/bool.hpp>
44 
45 #include <rclcpp/rclcpp.hpp>
46 
47 #include <chrono>
48 #include <iostream>
49 #include <memory>
50 #include <mutex>
51 
55 
56 using automotive_platform_msgs::msg::GearCommand;
57 using automotive_platform_msgs::msg::GearFeedback;
58 using automotive_platform_msgs::msg::SpeedMode;
59 using automotive_platform_msgs::msg::SteeringFeedback;
60 using automotive_platform_msgs::msg::SteerMode;
61 using automotive_platform_msgs::msg::TurnSignalCommand;
62 using automotive_platform_msgs::msg::VelocityAccelCov;
63 using autoware_auto_msgs::msg::HighLevelControlCommand;
64 using autoware_auto_msgs::msg::RawControlCommand;
68 using autoware_auto_msgs::msg::VehicleStateCommand;
69 using autoware_auto_msgs::srv::AutonomyModeChange;
70 using ModeChangeRequest = autoware_auto_msgs::srv::AutonomyModeChange_Request;
71 
74 
75 namespace ssc_interface
76 {
77 
78 static constexpr float32_t STEERING_TO_TIRE_RATIO = 0.533F / 8.6F;
79 
81 class SSC_INTERFACE_PUBLIC SscInterface
83 {
84 public:
92  explicit SscInterface(
93  rclcpp::Node & node,
94  float32_t front_axle_to_cog,
95  float32_t rear_axle_to_cog,
96  float32_t max_accel_mps2,
97  float32_t max_decel_mps2,
98  float32_t max_yaw_rate_rad
99  );
101  ~SscInterface() noexcept override = default;
102 
107  bool8_t update(std::chrono::nanoseconds timeout) override;
112  bool8_t send_state_command(const VehicleStateCommand & msg) override;
117  bool8_t send_control_command(const HighLevelControlCommand & msg);
122  bool8_t send_control_command(const RawControlCommand & msg) override;
127  bool8_t send_control_command(const VehicleControlCommand & msg) override;
132  bool8_t handle_mode_change_request(ModeChangeRequest::SharedPtr request) override;
133 
134  static void kinematic_bicycle_model(
135  float32_t dt, float32_t l_r, float32_t l_f, VehicleKinematicState * vks);
136 
137 private:
138  // Publishers (to SSC)
139  rclcpp::Publisher<GearCommand>::SharedPtr m_gear_cmd_pub;
140  rclcpp::Publisher<SpeedMode>::SharedPtr m_speed_cmd_pub;
141  rclcpp::Publisher<SteerMode>::SharedPtr m_steer_cmd_pub;
142  rclcpp::Publisher<TurnSignalCommand>::SharedPtr m_turn_signal_cmd_pub;
143 
144  // Publishers (to Autoware)
145  rclcpp::Publisher<VehicleKinematicState>::SharedPtr m_kinematic_state_pub;
146 
147  // Subscribers (from SSC)
148  rclcpp::SubscriptionBase::SharedPtr m_dbw_state_sub, m_gear_feedback_sub, m_vel_accel_sub,
149  m_steer_sub;
150 
151  rclcpp::Logger m_logger;
152  float32_t m_front_axle_to_cog;
153  float32_t m_rear_axle_to_cog;
154  float32_t m_accel_limit;
155  float32_t m_decel_limit;
156  float32_t m_max_yaw_rate;
157  std::unique_ptr<DbwStateMachine> m_dbw_state_machine;
158 
159  // The vehicle kinematic state is stored because it needs information from
160  // both on_steer_report() and on_vel_accel_report().
161  VehicleKinematicState m_vehicle_kinematic_state;
162  bool m_seen_steer{false};
163  bool m_seen_vel_accel{false};
164  // In case both arrive at the same time
165  std::mutex m_vehicle_kinematic_state_mutex;
166 
167  void on_dbw_state_report(const std_msgs::msg::Bool::SharedPtr & msg);
168  void on_gear_report(const GearFeedback::SharedPtr & msg);
169  void on_steer_report(const SteeringFeedback::SharedPtr & msg);
170  void on_vel_accel_report(const VelocityAccelCov::SharedPtr & msg);
171 };
172 
173 } // namespace ssc_interface
174 
175 #endif // SSC_INTERFACE__SSC_INTERFACE_HPP_
autoware::motion::control::pure_pursuit::VehicleControlCommand
autoware_auto_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
ssc_interface
Definition: ssc_interface.hpp:75
motion::motion_testing_nodes::TrajectoryPoint
autoware_auto_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: motion_testing_publisher.hpp:36
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:44
autoware::common::types::TAU
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
types.hpp
This file includes common type definition.
autoware::drivers::vehicle_interface::DbwState
DbwState
Definition: dbw_state_machine.hpp:41
autoware::drivers::vehicle_interface::PlatformInterface
Definition: platform_interface.hpp:52
autoware::drivers::vehicle_interface::DbwStateMachine
Class for maintaining the DBW state.
Definition: dbw_state_machine.hpp:50
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
platform_interface.hpp
Base class for vehicle "translator".
dbw_state_machine.hpp
Base class for vehicle drivers.
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
ssc_interface::SscInterface
Class for interfacing with AS SSC.
Definition: ssc_interface.hpp:81
ssc_interface::STEERING_TO_TIRE_RATIO
static constexpr float32_t STEERING_TO_TIRE_RATIO
Definition: ssc_interface.hpp:78
ModeChangeRequest
autoware_auto_msgs::srv::AutonomyModeChange_Request ModeChangeRequest
Definition: ne_raptor_interface.hpp:120
visibility_control.hpp