15 #ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ 
   16 #define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ 
   18 #include <simulation_interface/simulation_api_schema.pb.h> 
   21 #include <geometry_msgs/msg/accel.hpp> 
   22 #include <geometry_msgs/msg/twist.hpp> 
   24 #include <rclcpp/rclcpp.hpp> 
   25 #include <sensor_msgs/msg/imu.hpp> 
   27 #include <traffic_simulator_msgs/msg/entity_status.hpp> 
   34   explicit ImuSensorBase(
const simulation_api_schema::ImuSensorConfiguration & configuration)
 
   52     const rclcpp::Time & current_ros_time,
 
   53     const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) 
const -> 
bool = 0;
 
   70     return {std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2)};
 
   74 template <
typename MessageType>
 
   79     const simulation_api_schema::ImuSensorConfiguration & configuration,
 
   80     const typename rclcpp::Publisher<MessageType>::SharedPtr & publisher)
 
   82     entity_name_(configuration.entity()),
 
   83     frame_id_(configuration.frame_id()),
 
   89     const rclcpp::Time & current_ros_time,
 
   90     const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) 
const -> 
bool override 
   92     for (
const auto & status : statuses) {
 
   93       if (status.name() == entity_name_) {
 
   96         publisher_->publish(generateMessage(current_ros_time, status_msg));
 
  104   auto generateMessage(
 
  105     const rclcpp::Time & current_ros_time,
 
  110   const typename rclcpp::Publisher<MessageType>::SharedPtr publisher_;
 
Definition: imu_sensor.hpp:32
virtual ~ImuSensorBase()=default
std::mt19937 random_generator_
Definition: imu_sensor.hpp:60
const double noise_standard_deviation_orientation_
Definition: imu_sensor.hpp:57
std::normal_distribution noise_distribution_orientation_
Definition: imu_sensor.hpp:61
const std::array< double, 9 > linear_acceleration_covariance_
Definition: imu_sensor.hpp:66
std::normal_distribution noise_distribution_twist_
Definition: imu_sensor.hpp:62
const bool add_gravity_
Definition: imu_sensor.hpp:56
const std::array< double, 9 > angular_velocity_covariance_
Definition: imu_sensor.hpp:65
auto calculateCovariance(const double stddev) const -> std::array< double, 9 >
Definition: imu_sensor.hpp:68
virtual auto update(const rclcpp::Time ¤t_ros_time, const std::vector< traffic_simulator_msgs::EntityStatus > &statuses) const -> bool=0
ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration &configuration)
Definition: imu_sensor.hpp:34
const double noise_standard_deviation_acceleration_
Definition: imu_sensor.hpp:59
const std::array< double, 9 > orientation_covariance_
Definition: imu_sensor.hpp:64
std::normal_distribution noise_distribution_acceleration_
Definition: imu_sensor.hpp:63
const double noise_standard_deviation_twist_
Definition: imu_sensor.hpp:58
Definition: imu_sensor.hpp:76
ImuSensor(const simulation_api_schema::ImuSensorConfiguration &configuration, const typename rclcpp::Publisher< MessageType >::SharedPtr &publisher)
Definition: imu_sensor.hpp:78
auto update(const rclcpp::Time ¤t_ros_time, const std::vector< traffic_simulator_msgs::EntityStatus > &statuses) const -> bool override
Definition: imu_sensor.hpp:88
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