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 <atomic>
19 #include <autoware_control_msgs/msg/control.hpp>
20 #include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
21 #include <autoware_vehicle_msgs/msg/gear_command.hpp>
22 #include <autoware_vehicle_msgs/msg/gear_report.hpp>
23 #include <autoware_vehicle_msgs/msg/steering_report.hpp>
24 #include <autoware_vehicle_msgs/msg/turn_indicators_command.hpp>
25 #include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>
26 #include <autoware_vehicle_msgs/msg/velocity_report.hpp>
27 #include <autoware_vehicle_msgs/srv/control_mode_command.hpp>
31 #include <concealer/visibility.hpp>
32 #include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
33 #include <geometry_msgs/msg/pose.hpp>
34 #include <geometry_msgs/msg/twist_stamped.hpp>
35 #include <nav_msgs/msg/odometry.hpp>
36 #include <rclcpp/rclcpp.hpp>
37 #include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
38 
39 namespace concealer
40 {
41 class AutowareUniverse : public rclcpp::Node,
42  public ContinuousTransformBroadcaster<AutowareUniverse>
43 {
44 public:
45  // clang-format off
46  using AccelWithCovarianceStamped = geometry_msgs::msg::AccelWithCovarianceStamped;
47  using Control = autoware_control_msgs::msg::Control;
48  using ControlModeCommand = autoware_vehicle_msgs::srv::ControlModeCommand;
49  using ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport;
50  using GearCommand = autoware_vehicle_msgs::msg::GearCommand;
51  using GearReport = autoware_vehicle_msgs::msg::GearReport;
52  using Odometry = nav_msgs::msg::Odometry;
53  using PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId;
54  using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;
55  using SteeringReport = autoware_vehicle_msgs::msg::SteeringReport;
56  using TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
57  using TurnIndicatorsReport = autoware_vehicle_msgs::msg::TurnIndicatorsReport;
58  using VelocityReport = autoware_vehicle_msgs::msg::VelocityReport;
59 
64 
73 
74  std::atomic<geometry_msgs::msg::Accel> current_acceleration;
75  std::atomic<geometry_msgs::msg::Pose> current_pose;
76  std::atomic<geometry_msgs::msg::Twist> current_twist;
77  // clang-format on
78 
79 private:
80  rclcpp::Service<ControlModeCommand>::SharedPtr control_mode_request_server;
81 
82  const rclcpp::TimerBase::SharedPtr localization_update_timer;
83 
84  const rclcpp::TimerBase::SharedPtr vehicle_state_update_timer;
85 
86  std::thread localization_and_vehicle_state_update_thread;
87 
88  std::atomic<bool> is_stop_requested = false;
89 
90  std::atomic<std::uint8_t> current_control_mode = ControlModeReport::AUTONOMOUS;
91 
92  std::atomic<bool> is_thrown = false;
93 
94  std::exception_ptr thrown;
95 
96 public:
97  CONCEALER_PUBLIC explicit AutowareUniverse(bool);
98 
100 
101  auto rethrow() -> void;
102 
103  auto updateLocalization() -> void;
104 
105  auto updateVehicleState() -> void;
106 
107  auto getVehicleCommand() const -> std::tuple<double, double, double, double, int>;
108 
109  auto getRouteLanelets() const -> std::vector<std::int64_t>;
110 
111  auto getControlModeReport() const -> ControlModeReport;
112 
113  auto setManualMode() -> void;
114 };
115 } // namespace concealer
116 
117 #endif // CONCEALER__AUTOWARE_UNIVERSE_HPP_
Definition: autoware_universe.hpp:43
auto updateLocalization() -> void
Definition: autoware_universe.cpp:94
PublisherWrapper< GearReport > setGearReport
Definition: autoware_universe.hpp:69
autoware_vehicle_msgs::msg::GearReport GearReport
Definition: autoware_universe.hpp:51
autoware_vehicle_msgs::msg::GearCommand GearCommand
Definition: autoware_universe.hpp:50
auto getRouteLanelets() const -> std::vector< std::int64_t >
Definition: autoware_universe.cpp:211
autoware_vehicle_msgs::srv::ControlModeCommand ControlModeCommand
Definition: autoware_universe.hpp:48
autoware_control_msgs::msg::Control Control
Definition: autoware_universe.hpp:47
autoware_vehicle_msgs::msg::ControlModeReport ControlModeReport
Definition: autoware_universe.hpp:49
SubscriberWrapper< Control > getCommand
Definition: autoware_universe.hpp:60
PublisherWrapper< SteeringReport > setSteeringReport
Definition: autoware_universe.hpp:68
autoware_vehicle_msgs::msg::SteeringReport SteeringReport
Definition: autoware_universe.hpp:55
auto getVehicleCommand() const -> std::tuple< double, double, double, double, int >
Definition: autoware_universe.cpp:175
autoware_vehicle_msgs::msg::TurnIndicatorsCommand TurnIndicatorsCommand
Definition: autoware_universe.hpp:56
autoware_vehicle_msgs::msg::TurnIndicatorsReport TurnIndicatorsReport
Definition: autoware_universe.hpp:57
PublisherWrapper< TurnIndicatorsReport > setTurnIndicatorsReport
Definition: autoware_universe.hpp:72
~AutowareUniverse()
Definition: autoware_universe.cpp:81
autoware_vehicle_msgs::msg::VelocityReport VelocityReport
Definition: autoware_universe.hpp:58
tier4_planning_msgs::msg::PathWithLaneId PathWithLaneId
Definition: autoware_universe.hpp:53
CONCEALER_PUBLIC AutowareUniverse(bool)
Definition: autoware_universe.cpp:19
std::atomic< geometry_msgs::msg::Twist > current_twist
Definition: autoware_universe.hpp:76
geometry_msgs::msg::AccelWithCovarianceStamped AccelWithCovarianceStamped
Definition: autoware_universe.hpp:46
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: autoware_universe.hpp:54
std::atomic< geometry_msgs::msg::Pose > current_pose
Definition: autoware_universe.hpp:75
PublisherWrapper< VelocityReport > setVelocityReport
Definition: autoware_universe.hpp:71
PublisherWrapper< AccelWithCovarianceStamped > setAcceleration
Definition: autoware_universe.hpp:65
auto getControlModeReport() const -> ControlModeReport
Definition: autoware_universe.cpp:220
nav_msgs::msg::Odometry Odometry
Definition: autoware_universe.hpp:52
PublisherWrapper< PoseWithCovarianceStamped > setPose
Definition: autoware_universe.hpp:67
auto updateVehicleState() -> void
Definition: autoware_universe.cpp:138
std::atomic< geometry_msgs::msg::Accel > current_acceleration
Definition: autoware_universe.hpp:74
SubscriberWrapper< PathWithLaneId > getPathWithLaneId
Definition: autoware_universe.hpp:63
SubscriberWrapper< TurnIndicatorsCommand > getTurnIndicatorsCommand
Definition: autoware_universe.hpp:62
SubscriberWrapper< GearCommand > getGearCommand
Definition: autoware_universe.hpp:61
auto rethrow() -> void
Definition: autoware_universe.cpp:87
auto setManualMode() -> void
Definition: autoware_universe.cpp:227
PublisherWrapper< Odometry > setOdometry
Definition: autoware_universe.hpp:66
PublisherWrapper< ControlModeReport > setControlModeReport
Definition: autoware_universe.hpp:70
Definition: continuous_transform_broadcaster.hpp:30
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: autoware_universe.hpp:40
Definition: cache.hpp:27