scenario_simulator_v2 C++ API
publisher.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__PUBLISHER_HPP_
16 #define CONCEALER__PUBLISHER_HPP_
17 
18 #include <autoware_vehicle_msgs/msg/velocity_report.hpp>
19 #include <get_parameter/get_parameter.hpp>
20 #include <nav_msgs/msg/odometry.hpp>
21 #include <random>
22 #include <rclcpp/rclcpp.hpp>
23 
24 namespace concealer
25 {
26 template <typename>
27 struct Identity
28 {
29  explicit constexpr Identity(
30  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &)
31  {
32  }
33 
34  template <typename T>
35  constexpr auto operator()(T && x) const -> decltype(auto)
36  {
37  return std::forward<decltype(x)>(x);
38  }
39 };
40 
41 template <typename ValueType>
43 {
44  static_assert(std::is_floating_point_v<std::decay_t<ValueType> >, "Unsupported error type");
45 
46  std::normal_distribution<ValueType> additive, multiplicative;
47 
49  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node,
50  const std::string & prefix)
51  // clang-format off
52  : additive(
53  static_cast<ValueType>(common::getParameter<double>(node, prefix + ".additive.mean")),
54  static_cast<ValueType>(common::getParameter<double>(node, prefix + ".additive.standard_deviation"))),
56  static_cast<ValueType>(common::getParameter<double>(node, prefix + ".multiplicative.mean")),
57  static_cast<ValueType>(common::getParameter<double>(node, prefix + ".multiplicative.standard_deviation")))
58  // clang-format on
59  {
60  }
61 
62  auto apply(std::mt19937_64 & engine, const ValueType value) -> decltype(auto)
63  {
64  return value * (multiplicative(engine) + static_cast<ValueType>(1)) + additive(engine);
65  }
66 };
67 
68 template <typename>
70 
77 {
78  const std::random_device::result_type seed;
79 
80  std::mt19937_64 engine;
81 
82  explicit RandomNumberEngine(
83  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node,
84  const std::string & topic);
85 };
86 
87 template <>
88 struct NormalDistribution<nav_msgs::msg::Odometry> : public RandomNumberEngine
89 {
91 
92  // clang-format off
105  // clang-format on
106 
107  explicit NormalDistribution(
108  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &);
109 
110  auto operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry;
111 };
112 
113 template <>
114 struct NormalDistribution<autoware_vehicle_msgs::msg::VelocityReport> : public RandomNumberEngine
115 {
117 
118  // clang-format off
122  // clang-format on
123 
124  explicit NormalDistribution(
125  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &);
126 
127  auto operator()(autoware_vehicle_msgs::msg::VelocityReport velocity_report)
128  -> autoware_vehicle_msgs::msg::VelocityReport;
129 };
130 
131 template <typename Message, template <typename> typename Randomizer = Identity>
133 {
134  typename rclcpp::Publisher<Message>::SharedPtr publisher;
135 
136  Randomizer<Message> randomize;
137 
138 public:
139  template <typename Node>
140  explicit Publisher(const std::string & topic, Node & node)
141  : publisher(node.template create_publisher<Message>(topic, rclcpp::QoS(1).reliable())),
142  randomize(node.get_node_parameters_interface(), topic)
143  {
144  }
145 
146  template <typename... Ts>
147  auto operator()(Ts &&... xs) -> decltype(auto)
148  {
149  return publisher->publish(randomize(std::forward<decltype(xs)>(xs)...));
150  }
151 
152  auto getRandomizer() const noexcept -> const Randomizer<Message> & { return randomize; }
153  auto getRandomizer() noexcept -> Randomizer<Message> & { return randomize; }
154 };
155 } // namespace concealer
156 
157 #endif // CONCEALER__PUBLISHER_HPP_
Definition: publisher.hpp:133
auto operator()(Ts &&... xs) -> decltype(auto)
Definition: publisher.hpp:147
auto getRandomizer() const noexcept -> const Randomizer< Message > &
Definition: publisher.hpp:152
auto getRandomizer() noexcept -> Randomizer< Message > &
Definition: publisher.hpp:153
Publisher(const std::string &topic, Node &node)
Definition: publisher.hpp:140
Definition: concatenate.hpp:24
Definition: autoware_universe.hpp:40
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: publisher.hpp:28
constexpr Identity(const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &)
Definition: publisher.hpp:29
constexpr auto operator()(T &&x) const -> decltype(auto)
Definition: publisher.hpp:35
Definition: publisher.hpp:43
std::normal_distribution< ValueType > multiplicative
Definition: publisher.hpp:46
auto apply(std::mt19937_64 &engine, const ValueType value) -> decltype(auto)
Definition: publisher.hpp:62
NormalDistributionError(const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node, const std::string &prefix)
Definition: publisher.hpp:48
std::normal_distribution< ValueType > additive
Definition: publisher.hpp:44
NormalDistributionError< float > heading_rate_error
Definition: publisher.hpp:121
NormalDistributionError< float > longitudinal_velocity_error
Definition: publisher.hpp:119
NormalDistributionError< float > lateral_velocity_error
Definition: publisher.hpp:120
NormalDistributionError< double > linear_x_error
Definition: publisher.hpp:99
NormalDistributionError< double > orientation_r_error
Definition: publisher.hpp:96
NormalDistributionError< double > angular_y_error
Definition: publisher.hpp:103
NormalDistributionError< double > linear_z_error
Definition: publisher.hpp:101
NormalDistributionError< double > position_local_z_error
Definition: publisher.hpp:95
NormalDistributionError< double > position_local_x_error
Definition: publisher.hpp:93
NormalDistributionError< double > orientation_y_error
Definition: publisher.hpp:98
NormalDistributionError< double > position_local_y_error
Definition: publisher.hpp:94
double speed_threshold
Definition: publisher.hpp:90
NormalDistributionError< double > linear_y_error
Definition: publisher.hpp:100
NormalDistributionError< double > angular_z_error
Definition: publisher.hpp:104
NormalDistributionError< double > orientation_p_error
Definition: publisher.hpp:97
NormalDistributionError< double > angular_x_error
Definition: publisher.hpp:102
Definition: publisher.hpp:69
Provides common components for obtaining the seed and initializing the pseudo random number generator...
Definition: publisher.hpp:77
std::mt19937_64 engine
Definition: publisher.hpp:80
const std::random_device::result_type seed
Definition: publisher.hpp:78
RandomNumberEngine(const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node, const std::string &topic)
Definition: publisher.cpp:21