Autoware.Auto
ssc_interface.hpp
Go to the documentation of this file.
1 // Copyright 2020-2021 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 <autoware_auto_control_msgs/msg/high_level_control_command.hpp>
29 
30 #include <autoware_auto_planning_msgs/msg/trajectory_point.hpp>
31 
32 #include <automotive_platform_msgs/msg/gear_command.hpp>
33 #include <automotive_platform_msgs/msg/gear_feedback.hpp>
34 #include <automotive_platform_msgs/msg/speed_mode.hpp>
35 #include <automotive_platform_msgs/msg/steering_feedback.hpp>
36 #include <automotive_platform_msgs/msg/steer_mode.hpp>
37 #include <automotive_platform_msgs/msg/turn_signal_command.hpp>
38 #include <automotive_platform_msgs/msg/velocity_accel_cov.hpp>
39 
40 #include <autoware_auto_vehicle_msgs/msg/headlights_command.hpp>
41 #include <autoware_auto_vehicle_msgs/msg/raw_control_command.hpp>
42 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
43 #include <autoware_auto_vehicle_msgs/msg/vehicle_control_command.hpp>
44 #include <autoware_auto_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
45 #include <autoware_auto_vehicle_msgs/msg/vehicle_state_command.hpp>
46 #include <autoware_auto_vehicle_msgs/msg/vehicle_state_report.hpp>
47 #include <autoware_auto_vehicle_msgs/srv/autonomy_mode_change.hpp>
48 
49 #include <std_msgs/msg/bool.hpp>
50 
51 #include <rclcpp/rclcpp.hpp>
52 
53 #include <chrono>
54 #include <iostream>
55 #include <memory>
56 #include <mutex>
57 
61 
62 using SscGearCommand = automotive_platform_msgs::msg::GearCommand;
63 using automotive_platform_msgs::msg::GearFeedback;
64 using automotive_platform_msgs::msg::SpeedMode;
65 using automotive_platform_msgs::msg::SteeringFeedback;
66 using automotive_platform_msgs::msg::SteerMode;
67 using automotive_platform_msgs::msg::TurnSignalCommand;
68 using automotive_platform_msgs::msg::VelocityAccelCov;
69 using autoware_auto_vehicle_msgs::msg::HeadlightsCommand;
70 using autoware_auto_control_msgs::msg::HighLevelControlCommand;
71 using autoware_auto_vehicle_msgs::msg::RawControlCommand;
74 using autoware_auto_control_msgs::msg::AckermannControlCommand;
76 using autoware_auto_vehicle_msgs::msg::VehicleStateCommand;
77 using autoware_auto_vehicle_msgs::srv::AutonomyModeChange;
78 using ModeChangeRequest = autoware_auto_vehicle_msgs::srv::AutonomyModeChange_Request;
79 
82 
83 namespace ssc_interface
84 {
85 
86 static constexpr float32_t STEERING_TO_TIRE_RATIO = 0.533F / 8.6F;
87 
89 class SSC_INTERFACE_PUBLIC SscInterface
91 {
92 public:
100  explicit SscInterface(
101  rclcpp::Node & node,
102  float32_t front_axle_to_cog,
103  float32_t rear_axle_to_cog,
104  float32_t max_accel_mps2,
105  float32_t max_decel_mps2,
106  float32_t max_yaw_rate_rad
107  );
109  ~SscInterface() noexcept override = default;
110 
115  bool8_t update(std::chrono::nanoseconds timeout) override;
120  bool8_t send_state_command(const VehicleStateCommand & msg) override;
125  bool8_t send_control_command(const HighLevelControlCommand & msg);
130  bool8_t send_control_command(const RawControlCommand & msg) override;
135  bool8_t send_control_command(const VehicleControlCommand & msg) override;
140  bool8_t send_control_command(const AckermannControlCommand & msg) override;
145  bool8_t handle_mode_change_request(ModeChangeRequest::SharedPtr request) override;
146 
147  static void kinematic_bicycle_model(
148  float32_t dt, float32_t l_r, float32_t l_f, VehicleKinematicState * vks);
149 
150 private:
151  // Publishers (to SSC)
152  rclcpp::Publisher<SscGearCommand>::SharedPtr m_gear_cmd_pub;
153  rclcpp::Publisher<SpeedMode>::SharedPtr m_speed_cmd_pub;
154  rclcpp::Publisher<SteerMode>::SharedPtr m_steer_cmd_pub;
155  rclcpp::Publisher<TurnSignalCommand>::SharedPtr m_turn_signal_cmd_pub;
156 
157  // Publishers (to Autoware)
158  rclcpp::Publisher<VehicleKinematicState>::SharedPtr m_kinematic_state_pub;
159 
160  // Subscribers (from SSC)
161  rclcpp::SubscriptionBase::SharedPtr m_dbw_state_sub, m_gear_feedback_sub, m_vel_accel_sub,
162  m_steer_sub;
163 
164  rclcpp::Logger m_logger;
165  float32_t m_front_axle_to_cog;
166  float32_t m_rear_axle_to_cog;
167  float32_t m_accel_limit;
168  float32_t m_decel_limit;
169  std::unique_ptr<DbwStateMachine> m_dbw_state_machine;
170 
171  // The vehicle kinematic state is stored because it needs information from
172  // both on_steer_report() and on_vel_accel_report().
173  VehicleKinematicState m_vehicle_kinematic_state;
174  bool m_seen_steer{false};
175  bool m_seen_vel_accel{false};
176  // In case both arrive at the same time
177  std::mutex m_vehicle_kinematic_state_mutex;
178 
179  void on_dbw_state_report(const std_msgs::msg::Bool::SharedPtr & msg);
180  void on_gear_report(const GearFeedback::SharedPtr & msg);
181  void on_steer_report(const SteeringFeedback::SharedPtr & msg);
182  void on_vel_accel_report(const VelocityAccelCov::SharedPtr & msg);
183 };
184 
185 } // namespace ssc_interface
186 
187 #endif // SSC_INTERFACE__SSC_INTERFACE_HPP_
motion::motion_testing_nodes::TrajectoryPoint
autoware_auto_planning_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: motion_testing_publisher.hpp:36
ssc_interface
Definition: ssc_interface.hpp:83
autoware::common::types::TAU
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
autoware::motion::control::pure_pursuit::VehicleControlCommand
autoware_auto_vehicle_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
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:80
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".
sys_info_node.node
node
Definition: sys_info_node.py:23
dbw_state_machine.hpp
Base class for vehicle drivers.
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
SscGearCommand
automotive_platform_msgs::msg::GearCommand SscGearCommand
Definition: ssc_interface.hpp:62
ssc_interface::SscInterface
Class for interfacing with AS SSC.
Definition: ssc_interface.hpp:89
ssc_interface::STEERING_TO_TIRE_RATIO
static constexpr float32_t STEERING_TO_TIRE_RATIO
Definition: ssc_interface.hpp:86
ModeChangeRequest
autoware_auto_vehicle_msgs::srv::AutonomyModeChange_Request ModeChangeRequest
Definition: ne_raptor_interface.hpp:128
autoware::trajectory_spoofer::VehicleKinematicState
autoware_auto_vehicle_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:42
visibility_control.hpp