scenario_simulator_v2 C++ API
imu_sensor.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 SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_
16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_
17 
18 #include <simulation_interface/simulation_api_schema.pb.h>
19 
20 #include <array>
21 #include <concealer/publisher.hpp>
22 #include <geometry_msgs/msg/accel.hpp>
23 #include <geometry_msgs/msg/twist.hpp>
24 #include <random>
25 #include <rclcpp/rclcpp.hpp>
26 #include <sensor_msgs/msg/imu.hpp>
28 #include <traffic_simulator_msgs/msg/entity_status.hpp>
29 
31 {
33 {
34 public:
35  explicit ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration & configuration)
36  : add_gravity_(configuration.add_gravity()),
37  noise_standard_deviation_orientation_(configuration.noise_standard_deviation_orientation()),
38  noise_standard_deviation_twist_(configuration.noise_standard_deviation_twist()),
39  noise_standard_deviation_acceleration_(configuration.noise_standard_deviation_acceleration()),
40  random_generator_(configuration.use_seed() ? configuration.seed() : std::random_device{}()),
47  {
48  }
49 
50  virtual ~ImuSensorBase() = default;
51 
52  virtual auto update(
53  const rclcpp::Time & current_ros_time,
54  const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) -> bool = 0;
55 
56 protected:
57  const bool add_gravity_;
61  mutable std::mt19937 random_generator_;
62  mutable std::normal_distribution<> noise_distribution_orientation_;
63  mutable std::normal_distribution<> noise_distribution_twist_;
64  mutable std::normal_distribution<> noise_distribution_acceleration_;
65  std::array<double, 9> orientation_covariance_;
66  std::array<double, 9> angular_velocity_covariance_;
67  std::array<double, 9> linear_acceleration_covariance_;
68 
69  auto calculateCovariance(const double stddev) const -> std::array<double, 9>
70  {
71  return {std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2)};
72  }
73 };
74 
75 template <typename MessageType>
76 class ImuSensor : public ImuSensorBase
77 {
78 public:
79  template <typename NodeType>
80  explicit ImuSensor(
81  const simulation_api_schema::ImuSensorConfiguration & configuration, const std::string & topic,
82  NodeType & node)
83  : ImuSensorBase(configuration),
84  override_legacy_configuration_(common::getParameter<bool>(
85  node.get_node_parameters_interface(), topic + ".override_legacy_configuration", false)),
86  entity_name_(configuration.entity()),
87  frame_id_(configuration.frame_id()),
88  publish(topic, node)
89  {
90  if (not override_legacy_configuration_) {
91  publish.getRandomizer().active = false;
92  }
93  }
94 
95  auto update(
96  const rclcpp::Time & current_ros_time,
97  const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) -> bool override
98  {
99  for (const auto & status : statuses) {
100  if (status.name() == entity_name_) {
102  simulation_interface::toMsg(status, status_msg);
103  publish(generateMessage(current_ros_time, status_msg));
104  return true;
105  }
106  }
107  return false;
108  }
109 
110 private:
111  auto generateMessage(
112  const rclcpp::Time & current_ros_time,
113  const traffic_simulator_msgs::msg::EntityStatus & status) const -> const MessageType;
114 
115  const bool override_legacy_configuration_;
116  const std::string entity_name_;
117  const std::string frame_id_;
119 };
120 } // namespace simple_sensor_simulator
121 #endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_
auto getRandomizer() const noexcept -> const Randomizer< Message > &
Definition: publisher.hpp:212
Definition: imu_sensor.hpp:33
std::array< double, 9 > linear_acceleration_covariance_
Definition: imu_sensor.hpp:67
std::mt19937 random_generator_
Definition: imu_sensor.hpp:61
const double noise_standard_deviation_orientation_
Definition: imu_sensor.hpp:58
std::normal_distribution noise_distribution_orientation_
Definition: imu_sensor.hpp:62
std::array< double, 9 > angular_velocity_covariance_
Definition: imu_sensor.hpp:66
std::normal_distribution noise_distribution_twist_
Definition: imu_sensor.hpp:63
const bool add_gravity_
Definition: imu_sensor.hpp:57
auto calculateCovariance(const double stddev) const -> std::array< double, 9 >
Definition: imu_sensor.hpp:69
ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration &configuration)
Definition: imu_sensor.hpp:35
const double noise_standard_deviation_acceleration_
Definition: imu_sensor.hpp:60
virtual auto update(const rclcpp::Time &current_ros_time, const std::vector< traffic_simulator_msgs::EntityStatus > &statuses) -> bool=0
std::array< double, 9 > orientation_covariance_
Definition: imu_sensor.hpp:65
std::normal_distribution noise_distribution_acceleration_
Definition: imu_sensor.hpp:64
const double noise_standard_deviation_twist_
Definition: imu_sensor.hpp:59
Definition: imu_sensor.hpp:77
ImuSensor(const simulation_api_schema::ImuSensorConfiguration &configuration, const std::string &topic, NodeType &node)
Definition: imu_sensor.hpp:80
auto update(const rclcpp::Time &current_ros_time, const std::vector< traffic_simulator_msgs::EntityStatus > &statuses) -> bool override
Definition: imu_sensor.hpp:95
Definition: concatenate.hpp:24
Definition: constants.hpp:19
void toMsg(const geometry_msgs::Point &proto, geometry_msgs::msg::Point &p)
Definition: conversions.cpp:29
Definition: lanelet_wrapper.hpp:40
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32