scenario_simulator_v2 C++ API
behavior_plugin_base.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 TRAFFIC_SIMULATOR__BEHAVIOR__BEHAVIOR_PLUGIN_BASE_HPP_
16 #define TRAFFIC_SIMULATOR__BEHAVIOR__BEHAVIOR_PLUGIN_BASE_HPP_
17 
18 #include <optional>
19 #include <string>
25 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
26 #include <traffic_simulator_msgs/msg/entity_type.hpp>
27 #include <traffic_simulator_msgs/msg/obstacle.hpp>
28 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp>
29 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
30 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
31 #include <unordered_map>
32 #include <visualization_msgs/msg/marker_array.hpp>
33 
34 namespace entity_behavior
35 {
37  std::unordered_map<std::string, traffic_simulator::CanonicalizedEntityStatus>;
38 
40 {
41 public:
42  virtual ~BehaviorPluginBase() = default;
43  virtual void configure(const rclcpp::Logger & logger) = 0;
44  virtual void update(double current_time, double step_time) = 0;
45  virtual const std::string & getCurrentAction() const = 0;
46 
47 #define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \
48  virtual TYPE get##NAME() = 0; \
49  virtual void set##NAME(const TYPE & value) = 0; \
50  auto get##NAME##Key() const->const std::string & \
51  { \
52  static const std::string key = KEY; \
53  return key; \
54  }
55 
56  // clang-format off
57  DEFINE_GETTER_SETTER(BehaviorParameter, "behavior_parameter", traffic_simulator_msgs::msg::BehaviorParameter)
58  DEFINE_GETTER_SETTER(CurrentTime, "current_time", double)
59  DEFINE_GETTER_SETTER(DebugMarker, "debug_marker", std::vector<visualization_msgs::msg::Marker>)
60  DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, "matching_distance_for_lanelet_pose_calculation", double)
61  DEFINE_GETTER_SETTER(EntityStatus, "entity_status", std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>)
62  DEFINE_GETTER_SETTER(GoalPoses, "goal_poses", std::vector<geometry_msgs::msg::Pose>)
63  DEFINE_GETTER_SETTER(HdMapUtils, "hdmap_utils", std::shared_ptr<hdmap_utils::HdMapUtils>)
64  DEFINE_GETTER_SETTER(LaneChangeParameters, "lane_change_parameters", traffic_simulator::lane_change::Parameter)
65  DEFINE_GETTER_SETTER(Obstacle, "obstacle", std::optional<traffic_simulator_msgs::msg::Obstacle>)
66  DEFINE_GETTER_SETTER(OtherEntityStatus, "other_entity_status", EntityStatusDict)
67  DEFINE_GETTER_SETTER(PedestrianParameters, "pedestrian_parameters", traffic_simulator_msgs::msg::PedestrianParameters)
68  DEFINE_GETTER_SETTER(PolylineTrajectory, "polyline_trajectory", std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory>)
69  DEFINE_GETTER_SETTER(ReferenceTrajectory, "reference_trajectory", std::shared_ptr<math::geometry::CatmullRomSpline>)
71  DEFINE_GETTER_SETTER(RouteLanelets, "route_lanelets", lanelet::Ids)
72  DEFINE_GETTER_SETTER(StepTime, "step_time", double)
73  DEFINE_GETTER_SETTER(TargetSpeed, "target_speed", std::optional<double>)
74  DEFINE_GETTER_SETTER(TrafficLightManager, "traffic_light_manager", std::shared_ptr<traffic_simulator::TrafficLightManager>)
75  DEFINE_GETTER_SETTER(UpdatedStatus, "updated_status", std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>)
76  DEFINE_GETTER_SETTER(VehicleParameters, "vehicle_parameters", traffic_simulator_msgs::msg::VehicleParameters)
77  DEFINE_GETTER_SETTER(Waypoints, "waypoints", traffic_simulator_msgs::msg::WaypointsArray)
78  // clang-format on
79 #undef DEFINE_GETTER_SETTER
80 };
81 } // namespace entity_behavior
82 
83 #endif // TRAFFIC_SIMULATOR__BEHAVIOR__BEHAVIOR_PLUGIN_BASE_HPP_
#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE)
Definition: behavior_plugin_base.hpp:47
Definition: behavior_plugin_base.hpp:40
virtual void update(double current_time, double step_time)=0
virtual void configure(const rclcpp::Logger &logger)=0
virtual const std::string & getCurrentAction() const =0
Definition: action_node.hpp:38
std::unordered_map< std::string, traffic_simulator::CanonicalizedEntityStatus > EntityStatusDict
Definition: behavior_plugin_base.hpp:37
Definition: cache.hpp:46
Definition: bounding_box.hpp:32
Definition: cache.hpp:27
Request
Definition: behavior.hpp:25
Definition: api.hpp:48
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:24
std::string string
Definition: junit5.hpp:26