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>
22 #include <geometry_msgs/msg/accel.hpp>
23 #include <geometry_msgs/msg/twist.hpp>
25 #include <rclcpp/rclcpp.hpp>
26 #include <sensor_msgs/msg/imu.hpp>
28 #include <traffic_simulator_msgs/msg/entity_status.hpp>
35 explicit ImuSensorBase(
const simulation_api_schema::ImuSensorConfiguration & configuration)
53 const rclcpp::Time & current_ros_time,
54 const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) ->
bool = 0;
71 return {std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2)};
75 template <
typename MessageType>
79 template <
typename NodeType>
81 const simulation_api_schema::ImuSensorConfiguration & configuration,
const std::string & topic,
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()),
90 if (not override_legacy_configuration_) {
96 const rclcpp::Time & current_ros_time,
97 const std::vector<traffic_simulator_msgs::EntityStatus> & statuses) ->
bool override
99 for (
const auto & status : statuses) {
100 if (status.name() == entity_name_) {
103 publish(generateMessage(current_ros_time, status_msg));
111 auto generateMessage(
112 const rclcpp::Time & current_ros_time,
115 const bool override_legacy_configuration_;
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
virtual ~ImuSensorBase()=default
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 ¤t_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 ¤t_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