scenario_simulator_v2 C++ API
autoware.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_HPP_
16 #define CONCEALER__AUTOWARE_HPP_
17 
18 #include <atomic>
19 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
20 #include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
21 #include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
23 #include <concealer/visibility.hpp>
24 #include <geometry_msgs/msg/accel.hpp>
25 #include <geometry_msgs/msg/pose.hpp>
26 #include <geometry_msgs/msg/twist_stamped.hpp>
27 #include <rclcpp/rclcpp.hpp>
28 
29 namespace concealer
30 {
37 class Autoware : public rclcpp::Node, public ContinuousTransformBroadcaster<Autoware>
38 {
39 protected:
40  std::atomic<geometry_msgs::msg::Accel> current_acceleration;
41 
42  std::atomic<geometry_msgs::msg::Twist> current_twist;
43 
44  std::atomic<geometry_msgs::msg::Pose> current_pose;
45 
46 public:
47  CONCEALER_PUBLIC explicit Autoware();
48 
49  virtual auto getAcceleration() const -> double = 0;
50 
51  virtual auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand;
52 
53  virtual auto getSteeringAngle() const -> double = 0;
54 
55  virtual auto getVelocity() const -> double = 0;
56 
57  // returns -1.0 when gear is reverse and 1.0 otherwise
58  virtual auto getGearSign() const -> double = 0;
59 
60  virtual auto getTurnIndicatorsCommand() const
61  -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand;
62 
63  virtual auto getVehicleCommand() const -> std::tuple<
64  autoware_auto_control_msgs::msg::AckermannControlCommand,
65  autoware_auto_vehicle_msgs::msg::GearCommand> = 0;
66 
67  virtual auto getRouteLanelets() const -> std::vector<std::int64_t> = 0;
68 
69  auto set(const geometry_msgs::msg::Accel &) -> void;
70 
71  auto set(const geometry_msgs::msg::Twist &) -> void;
72 
73  auto set(const geometry_msgs::msg::Pose &) -> void;
74 
75  virtual auto rethrow() -> void;
76 };
77 } // namespace concealer
78 
79 #endif // CONCEALER__AUTOWARE_HPP_
Definition: autoware.hpp:38
virtual auto getAcceleration() const -> double=0
virtual auto getRouteLanelets() const -> std::vector< std::int64_t >=0
auto set(const geometry_msgs::msg::Accel &) -> void
Definition: autoware.cpp:38
virtual auto rethrow() -> void
Definition: autoware.cpp:60
std::atomic< geometry_msgs::msg::Pose > current_pose
Definition: autoware.hpp:44
virtual auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand
Definition: autoware.cpp:27
virtual auto getVehicleCommand() const -> std::tuple< autoware_auto_control_msgs::msg::AckermannControlCommand, autoware_auto_vehicle_msgs::msg::GearCommand >=0
virtual auto getVelocity() const -> double=0
std::atomic< geometry_msgs::msg::Accel > current_acceleration
Definition: autoware.hpp:40
virtual auto getGearSign() const -> double=0
CONCEALER_PUBLIC Autoware()
Definition: autoware.cpp:19
virtual auto getSteeringAngle() const -> double=0
virtual auto getTurnIndicatorsCommand() const -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand
Definition: autoware.cpp:47
std::atomic< geometry_msgs::msg::Twist > current_twist
Definition: autoware.hpp:42
Definition: continuous_transform_broadcaster.hpp:30
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: field_operator_application.hpp:161
Definition: autoware.hpp:30
Definition: cache.hpp:27