15 #ifndef DO_NOTHING_PLUGIN__PEDESTRIAN__PLUGIN_HPP_
16 #define DO_NOTHING_PLUGIN__PEDESTRIAN__PLUGIN_HPP_
30 void update(
double current_time,
double step_time)
override;
35 void configure(
const rclcpp::Logger & logger)
override;
42 #define DEFINE_GETTER_SETTER(NAME, TYPE) \
44 TYPE get##NAME() override { return TYPE(); }; \
45 void set##NAME(const TYPE &) override{};
61 #undef DEFINE_GETTER_SETTER
64 #define DEFINE_GETTER_SETTER(NAME, TYPE, FIELD_NAME) \
66 TYPE get##NAME() override { return FIELD_NAME; }; \
67 void set##NAME(const TYPE & value) override { FIELD_NAME = value; }; \
72 DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter, behavior_parameter_)
81 #undef DEFINE_GETTER_SETTER
Definition: behavior_plugin_base.hpp:42
Definition: plugin.hpp:23
void update(double current_time, double step_time) override
just update timestamp of entity_status_ member variable.
Definition: plugin.cpp:163
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:158
auto getCurrentAction() -> const std::string &override
Get the Current Action object.
Definition: plugin.cpp:210
Definition: action_node.hpp:41
std::unordered_map< std::string, traffic_simulator::CanonicalizedEntityStatus > EntityStatusDict
Definition: behavior_plugin_base.hpp:37
std::unordered_map< std::pair< std::string, std::string >, double > EuclideanDistancesMap
Definition: behavior_plugin_base.hpp:39
Definition: bounding_box.hpp:32
Definition: lanelet_wrapper.hpp:40
Request
Definition: behavior.hpp:25
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
Definition: operators.hpp:25
std::string string
Definition: junit5.hpp:26
#define DEFINE_GETTER_SETTER(NAME, TYPE)
Definition: plugin.hpp:64