19 #ifndef SSC_INTERFACE__SSC_INTERFACE_HPP_
20 #define SSC_INTERFACE__SSC_INTERFACE_HPP_
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>
45 #include <rclcpp/rclcpp.hpp>
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;
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;
132 bool8_t handle_mode_change_request(ModeChangeRequest::SharedPtr request)
override;
134 static void kinematic_bicycle_model(
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;
145 rclcpp::Publisher<VehicleKinematicState>::SharedPtr m_kinematic_state_pub;
148 rclcpp::SubscriptionBase::SharedPtr m_dbw_state_sub, m_gear_feedback_sub, m_vel_accel_sub,
151 rclcpp::Logger m_logger;
157 std::unique_ptr<DbwStateMachine> m_dbw_state_machine;
162 bool m_seen_steer{
false};
163 bool m_seen_vel_accel{
false};
165 std::mutex m_vehicle_kinematic_state_mutex;
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);
175 #endif // SSC_INTERFACE__SSC_INTERFACE_HPP_