scenario_simulator_v2 C++ API
plugin.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 DO_NOTHING_PLUGIN__PEDESTRIAN__PLUGIN_HPP_
16 #define DO_NOTHING_PLUGIN__PEDESTRIAN__PLUGIN_HPP_
17 
19 
20 namespace entity_behavior
21 {
23 {
24 public:
30  void update(double current_time, double step_time) override;
35  void configure(const rclcpp::Logger & logger) override;
40  const std::string & getCurrentAction() const override;
41 
43 #define DEFINE_GETTER_SETTER(NAME, TYPE) \
44 public: \
45  TYPE get##NAME() override { return TYPE(); }; \
46  void set##NAME(const TYPE &) override{};
47  // clang-format off
48  DEFINE_GETTER_SETTER(DebugMarker, std::vector<visualization_msgs::msg::Marker>)
49  DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, double)
50  DEFINE_GETTER_SETTER(GoalPoses, std::vector<geometry_msgs::msg::Pose>)
51  DEFINE_GETTER_SETTER(LaneChangeParameters, traffic_simulator::lane_change::Parameter)
52  DEFINE_GETTER_SETTER(Obstacle, std::optional<traffic_simulator_msgs::msg::Obstacle>)
54  DEFINE_GETTER_SETTER(PedestrianParameters, traffic_simulator_msgs::msg::PedestrianParameters)
55  DEFINE_GETTER_SETTER(ReferenceTrajectory, std::shared_ptr<math::geometry::CatmullRomSpline>)
56  DEFINE_GETTER_SETTER(RouteLanelets, lanelet::Ids)
57  DEFINE_GETTER_SETTER(TargetSpeed, std::optional<double>)
58  DEFINE_GETTER_SETTER(TrafficLightManager, std::shared_ptr<traffic_simulator::TrafficLightManager>)
59  DEFINE_GETTER_SETTER(VehicleParameters, traffic_simulator_msgs::msg::VehicleParameters)
60  DEFINE_GETTER_SETTER(Waypoints, traffic_simulator_msgs::msg::WaypointsArray)
61  // clang-format on
62 #undef DEFINE_GETTER_SETTER
63 
65 #define DEFINE_GETTER_SETTER(NAME, TYPE, FIELD_NAME) \
66 public: \
67  TYPE get##NAME() override { return FIELD_NAME; }; \
68  void set##NAME(const TYPE & value) override { FIELD_NAME = value; }; \
69  \
70 private: \
71  TYPE FIELD_NAME;
72  // clang-format off
73  DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter, behavior_parameter_)
74  DEFINE_GETTER_SETTER(CurrentTime, double, current_time_)
75  DEFINE_GETTER_SETTER(EntityStatus, std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>, entity_status_)
76  DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr<hdmap_utils::HdMapUtils>, hdmap_utils_)
77  DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory>, polyline_trajectory)
79  DEFINE_GETTER_SETTER(StepTime, double, step_time_)
80  DEFINE_GETTER_SETTER(UpdatedStatus, std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>, updated_status_)
81  // clang-format on
82 #undef DEFINE_GETTER_SETTER
83 };
84 } // namespace entity_behavior
85 
86 #endif // DO_NOTHING_PLUGIN__PEDESTRIAN__PLUGIN_HPP_
Definition: behavior_plugin_base.hpp:40
Definition: plugin.hpp:23
void update(double current_time, double step_time) override
just update timestamp of entity_status_ member variable.
Definition: plugin.cpp:142
void configure(const rclcpp::Logger &logger) override
setup rclcpp::logger for debug output, but there is no debug output in this plugin.
Definition: plugin.cpp:140
const std::string & getCurrentAction() const override
Get the Current Action object.
Definition: plugin.cpp:173
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
#define DEFINE_GETTER_SETTER(NAME, TYPE)
Definition: plugin.hpp:65