scenario_simulator_v2 C++ API
autoware_universe.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
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 #ifndef CONCEALER__AUTOWARE_UNIVERSE_HPP_
16 #define CONCEALER__AUTOWARE_UNIVERSE_HPP_
17 
18 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
19 #include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
20 #include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
21 #include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
22 #include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
23 #include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp>
24 #include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
25 #include <concealer/autoware.hpp>
28 #include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
29 #include <nav_msgs/msg/odometry.hpp>
30 
31 namespace concealer
32 {
33 /*
34  * Implements Autoware interface for Autoware Universe
35  * NOTE: This class is intended to be move to simple_sensor_simulator
36  */
37 class AutowareUniverse : public Autoware
38 {
39  // clang-format off
44 
52  // clang-format on
53 
54  const rclcpp::TimerBase::SharedPtr localization_update_timer;
55 
56  const rclcpp::TimerBase::SharedPtr vehicle_state_update_timer;
57 
58  std::thread localization_and_vehicle_state_update_thread;
59 
60  std::atomic<bool> is_stop_requested = false;
61 
62  std::atomic<bool> is_thrown = false;
63 
64  std::exception_ptr thrown;
65 
66  auto stopAndJoin() -> void;
67 
68 public:
70 
72 
73  auto rethrow() -> void override;
74 
75  auto getAcceleration() const -> double override;
76 
77  auto getSteeringAngle() const -> double override;
78 
79  auto getVelocity() const -> double override;
80 
81  auto updateLocalization() -> void;
82 
83  auto updateVehicleState() -> void;
84 
85  auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand override;
86 
87  auto getGearSign() const -> double override;
88 
89  auto getVehicleCommand() const -> std::tuple<
90  autoware_auto_control_msgs::msg::AckermannControlCommand,
91  autoware_auto_vehicle_msgs::msg::GearCommand> override;
92 
93  auto getRouteLanelets() const -> std::vector<std::int64_t>;
94 };
95 
96 } // namespace concealer
97 
98 #endif // CONCEALER__AUTOWARE_UNIVERSE_HPP_
Definition: autoware_universe.hpp:38
auto updateLocalization() -> void
Definition: autoware_universe.cpp:81
auto getGearSign() const -> double override
Definition: autoware_universe.cpp:156
auto getRouteLanelets() const -> std::vector< std::int64_t >
Definition: autoware_universe.cpp:174
CONCEALER_PUBLIC AutowareUniverse()
Definition: autoware_universe.cpp:19
auto getVehicleCommand() const -> std::tuple< autoware_auto_control_msgs::msg::AckermannControlCommand, autoware_auto_vehicle_msgs::msg::GearCommand > override
Definition: autoware_universe.cpp:167
~AutowareUniverse()
Definition: autoware_universe.cpp:51
auto getSteeringAngle() const -> double override
Definition: autoware_universe.cpp:76
auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand override
Definition: autoware_universe.cpp:151
auto rethrow() -> void override
Definition: autoware_universe.cpp:53
auto getAcceleration() const -> double override
Definition: autoware_universe.cpp:66
auto updateVehicleState() -> void
Definition: autoware_universe.cpp:110
auto getVelocity() const -> double override
Definition: autoware_universe.cpp:71
Definition: autoware.hpp:38
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: autoware.hpp:30