Autoware.Auto
ne_raptor_interface.hpp
Go to the documentation of this file.
1 // Copyright 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 NE_RAPTOR_INTERFACE__NE_RAPTOR_INTERFACE_HPP_
20 #define NE_RAPTOR_INTERFACE__NE_RAPTOR_INTERFACE_HPP_
21 
23 
24 #include <common/types.hpp>
27 
28 #include <raptor_dbw_msgs/msg/accelerator_pedal_cmd.hpp>
29 #include <raptor_dbw_msgs/msg/brake_cmd.hpp>
30 #include <raptor_dbw_msgs/msg/gear_cmd.hpp>
31 #include <raptor_dbw_msgs/msg/global_enable_cmd.hpp>
32 #include <raptor_dbw_msgs/msg/misc_cmd.hpp>
33 #include <raptor_dbw_msgs/msg/steering_cmd.hpp>
34 
35 #include <raptor_dbw_msgs/msg/brake_report.hpp>
36 #include <raptor_dbw_msgs/msg/gear_report.hpp>
37 #include <raptor_dbw_msgs/msg/misc_report.hpp>
38 #include <raptor_dbw_msgs/msg/other_actuators_report.hpp>
39 #include <raptor_dbw_msgs/msg/steering_report.hpp>
40 #include <raptor_dbw_msgs/msg/wheel_speed_report.hpp>
41 
42 #include <raptor_dbw_msgs/msg/actuator_control_mode.hpp>
43 #include <raptor_dbw_msgs/msg/door_request.hpp>
44 #include <raptor_dbw_msgs/msg/door_state.hpp>
45 #include <raptor_dbw_msgs/msg/gear.hpp>
46 #include <raptor_dbw_msgs/msg/high_beam.hpp>
47 #include <raptor_dbw_msgs/msg/high_beam_state.hpp>
48 #include <raptor_dbw_msgs/msg/horn_state.hpp>
49 #include <raptor_dbw_msgs/msg/ignition.hpp>
50 #include <raptor_dbw_msgs/msg/low_beam.hpp>
51 #include <raptor_dbw_msgs/msg/parking_brake.hpp>
52 #include <raptor_dbw_msgs/msg/turn_signal.hpp>
53 #include <raptor_dbw_msgs/msg/wiper_front.hpp>
54 #include <raptor_dbw_msgs/msg/wiper_rear.hpp>
55 
56 #include <autoware_auto_msgs/msg/high_level_control_command.hpp>
57 #include <autoware_auto_msgs/msg/raw_control_command.hpp>
58 #include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
59 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp>
60 
61 #include <autoware_auto_msgs/msg/vehicle_state_report.hpp>
62 #include <autoware_auto_msgs/msg/vehicle_odometry.hpp>
63 #include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
64 
65 #include <autoware_auto_msgs/srv/autonomy_mode_change.hpp>
66 
67 #include <std_msgs/msg/bool.hpp>
69 #include <rclcpp/rclcpp.hpp>
70 #include <rclcpp/clock.hpp>
71 
72 #include <chrono>
73 #include <iostream>
74 #include <memory>
75 #include <mutex>
76 
81 
82 using raptor_dbw_msgs::msg::AcceleratorPedalCmd;
83 using raptor_dbw_msgs::msg::BrakeCmd;
84 using raptor_dbw_msgs::msg::GearCmd;
85 using raptor_dbw_msgs::msg::GlobalEnableCmd;
86 using raptor_dbw_msgs::msg::MiscCmd;
87 using raptor_dbw_msgs::msg::SteeringCmd;
88 
89 using raptor_dbw_msgs::msg::BrakeReport;
90 using raptor_dbw_msgs::msg::GearReport;
91 using raptor_dbw_msgs::msg::MiscReport;
92 using raptor_dbw_msgs::msg::OtherActuatorsReport;
93 using raptor_dbw_msgs::msg::SteeringReport;
94 using raptor_dbw_msgs::msg::WheelSpeedReport;
95 
96 using raptor_dbw_msgs::msg::ActuatorControlMode;
97 using raptor_dbw_msgs::msg::DoorRequest;
98 using raptor_dbw_msgs::msg::DoorState;
99 using raptor_dbw_msgs::msg::Gear;
100 using raptor_dbw_msgs::msg::HighBeam;
101 using raptor_dbw_msgs::msg::HighBeamState;
102 using raptor_dbw_msgs::msg::HornState;
103 using raptor_dbw_msgs::msg::Ignition;
104 using raptor_dbw_msgs::msg::LowBeam;
105 using raptor_dbw_msgs::msg::ParkingBrake;
106 using raptor_dbw_msgs::msg::TurnSignal;
107 using raptor_dbw_msgs::msg::WiperFront;
108 using raptor_dbw_msgs::msg::WiperRear;
109 
110 using autoware_auto_msgs::msg::HighLevelControlCommand;
111 using autoware_auto_msgs::msg::RawControlCommand;
113 using autoware_auto_msgs::msg::VehicleStateCommand;
114 
115 using autoware_auto_msgs::msg::VehicleStateReport;
116 using autoware_auto_msgs::msg::VehicleOdometry;
118 
119 using autoware_auto_msgs::srv::AutonomyModeChange;
120 using ModeChangeRequest = autoware_auto_msgs::srv::AutonomyModeChange_Request;
121 using ModeChangeResponse = autoware_auto_msgs::srv::AutonomyModeChange_Response;
122 
125 
126 namespace autoware
127 {
129 {
130 static constexpr float32_t KPH_TO_MPS_RATIO = 1000.0F / (60.0F * 60.0F);
131 static constexpr float32_t DEGREES_TO_RADIANS = PI / 180.0F;
132 static constexpr int64_t CLOCK_1_SEC = 1000; // duration in milliseconds
134 class NE_RAPTOR_INTERFACE_PUBLIC NERaptorInterface
136 {
137 public:
149  explicit NERaptorInterface(
150  rclcpp::Node & node,
151  uint16_t ecu_build_num,
152  float32_t front_axle_to_cog,
153  float32_t rear_axle_to_cog,
154  float32_t steer_to_tire_ratio,
155  float32_t max_steer_angle,
156  float32_t acceleration_limit,
157  float32_t deceleration_limit,
158  float32_t acceleration_positive_jerk_limit,
159  float32_t deceleration_negative_jerk_limit
160  );
162  ~NERaptorInterface() noexcept override = default;
163 
168  bool8_t update(std::chrono::nanoseconds timeout) override;
169 
174  bool8_t send_state_command(const VehicleStateCommand & msg) override;
175 
180  bool8_t send_control_command(const HighLevelControlCommand & msg);
181 
186  bool8_t send_control_command(const RawControlCommand & msg) override;
187 
193  bool8_t send_control_command(const VehicleControlCommand & msg) override;
194 
199  bool8_t handle_mode_change_request(ModeChangeRequest::SharedPtr request) override;
200 
205  void kinematic_bicycle_model(
206  float32_t dt, VehicleKinematicState * vks);
207 
208 private:
209  // Publishers (to Raptor DBW)
210  rclcpp::Publisher<AcceleratorPedalCmd>::SharedPtr m_accel_cmd_pub;
211  rclcpp::Publisher<BrakeCmd>::SharedPtr m_brake_cmd_pub;
212  rclcpp::Publisher<GearCmd>::SharedPtr m_gear_cmd_pub;
213  rclcpp::Publisher<GlobalEnableCmd>::SharedPtr m_global_enable_cmd_pub;
214  rclcpp::Publisher<MiscCmd>::SharedPtr m_misc_cmd_pub;
215  rclcpp::Publisher<SteeringCmd>::SharedPtr m_steer_cmd_pub;
216  rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr m_dbw_enable_cmd_pub;
217  rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr m_dbw_disable_cmd_pub;
218 
219  // Publishers (to Autoware)
220  rclcpp::Publisher<VehicleStateReport>::SharedPtr m_vehicle_state_pub;
221  rclcpp::Publisher<VehicleOdometry>::SharedPtr m_vehicle_odo_pub;
222  rclcpp::Publisher<VehicleKinematicState>::SharedPtr m_vehicle_kin_state_pub;
223 
224  // Subscribers (from Raptor DBW)
225  rclcpp::SubscriptionBase::SharedPtr
226  m_brake_rpt_sub, m_gear_rpt_sub, m_misc_rpt_sub,
227  m_other_acts_rpt_sub, m_steering_rpt_sub, m_wheel_spd_rpt_sub;
228 
229  rclcpp::Logger m_logger;
230  uint16_t m_ecu_build_num;
231  float32_t m_front_axle_to_cog;
232  float32_t m_rear_axle_to_cog;
233  float32_t m_steer_to_tire_ratio;
234  float32_t m_max_steer_angle;
235  float32_t m_acceleration_limit;
236  float32_t m_deceleration_limit;
237  float32_t m_acceleration_positive_jerk_limit;
238  float32_t m_deceleration_negative_jerk_limit;
239  std::unique_ptr<DbwStateMachine> m_dbw_state_machine;
240  uint8_t m_rolling_counter_vsc;
241  uint8_t m_rolling_counter_hlcc;
242  uint8_t m_rolling_counter_vcc;
243  rclcpp::Clock m_clock;
244 
245  /* Vehicle Odometry, Vehicle State, &
246  * Vehicle Kinematic State are stored
247  * because they need data from multiple reports.
248  *
249  * Similarly, Brake Command needs data
250  * from multiple commands.
251  */
252  VehicleOdometry m_vehicle_odometry{};
253  VehicleStateReport m_vehicle_state_report{};
254  VehicleKinematicState m_vehicle_kin_state{};
255  BrakeCmd m_brake_cmd{};
256  bool8_t m_seen_brake_rpt{false};
257  bool8_t m_seen_gear_rpt{false};
258  bool8_t m_seen_misc_rpt{false};
259  bool8_t m_seen_steering_rpt{false};
260  bool8_t m_seen_wheel_spd_rpt{false};
261  bool8_t m_seen_vehicle_state_cmd{false};
262  float32_t m_travel_direction{0.0F};
263 
264  // In case multiple signals arrive at the same time
265  std::mutex m_vehicle_odometry_mutex;
266  std::mutex m_vehicle_state_report_mutex;
267  std::mutex m_vehicle_kin_state_mutex;
268  std::mutex m_brake_cmd_mutex;
269 
275  void on_brake_report(const BrakeReport::SharedPtr & msg);
276 
282  void on_gear_report(const GearReport::SharedPtr & msg);
283 
292  void on_misc_report(const MiscReport::SharedPtr & msg);
293 
300  void on_other_actuators_report(const OtherActuatorsReport::SharedPtr & msg);
301 
308  void on_steering_report(const SteeringReport::SharedPtr & msg);
309 
315  void on_wheel_spd_report(const WheelSpeedReport::SharedPtr & msg);
316 }; // class NERaptorInterface
317 } // namespace ne_raptor_interface
318 } // namespace autoware
319 #endif // NE_RAPTOR_INTERFACE__NE_RAPTOR_INTERFACE_HPP_
autoware::motion::control::pure_pursuit::VehicleControlCommand
autoware_auto_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
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
autoware::ne_raptor_interface::DEGREES_TO_RADIANS
static constexpr float32_t DEGREES_TO_RADIANS
Definition: ne_raptor_interface.hpp:131
types.hpp
This file includes common type definition.
autoware::drivers::vehicle_interface::DbwState
DbwState
Definition: dbw_state_machine.hpp:41
ModeChangeResponse
autoware_auto_msgs::srv::AutonomyModeChange_Response ModeChangeResponse
Definition: ne_raptor_interface.hpp:121
ne_raptor_interface
Definition: ne_raptor_interface.launch.py:1
autoware::ne_raptor_interface::KPH_TO_MPS_RATIO
static constexpr float32_t KPH_TO_MPS_RATIO
Definition: ne_raptor_interface.hpp:130
autoware::drivers::vehicle_interface::PlatformInterface
Definition: platform_interface.hpp:52
autoware::ne_raptor_interface::CLOCK_1_SEC
static constexpr int64_t CLOCK_1_SEC
Definition: ne_raptor_interface.hpp:132
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
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
platform_interface.hpp
Base class for vehicle "translator".
dbw_state_machine.hpp
Base class for vehicle drivers.
motion_common.hpp
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
visibility_control.hpp
autoware::ne_raptor_interface::NERaptorInterface
Class for interfacing with NE Raptor DBW.
Definition: ne_raptor_interface.hpp:134
ModeChangeRequest
autoware_auto_msgs::srv::AutonomyModeChange_Request ModeChangeRequest
Definition: ne_raptor_interface.hpp:120
autoware::common::types::PI
constexpr float32_t PI
pi = tau / 2
Definition: types.hpp:50