scenario_simulator_v2 C++ API
helper.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 TRAFFIC_SIMULATOR__HELPER__HELPER_HPP_
16 #define TRAFFIC_SIMULATOR__HELPER__HELPER_HPP_
17 
18 #include <simulation_api_schema.pb.h>
19 
20 #include <algorithm>
21 #include <cmath>
22 #include <geometry_msgs/msg/pose.hpp>
23 #include <geometry_msgs/msg/quaternion.hpp>
24 #include <geometry_msgs/msg/vector3.hpp>
25 #include <iostream>
26 #include <string>
28 #include <traffic_simulator_msgs/msg/action_status.hpp>
29 #include <unordered_set>
30 #include <vector>
31 
32 namespace traffic_simulator
33 {
34 namespace helper
35 {
45 traffic_simulator_msgs::msg::ActionStatus constructActionStatus(
46  double linear_vel = 0, double angular_vel = 0, double linear_accel = 0, double angular_accel = 0);
47 
60  lanelet::Id lanelet_id, double s, double offset = 0, double roll = 0, double pitch = 0,
61  double yaw = 0);
62 
71 auto constructCanonicalizedLaneletPose(lanelet::Id lanelet_id, double s, double offset)
73 
86  lanelet::Id lanelet_id, double s, double offset, double roll, double pitch, double yaw)
88 
97 geometry_msgs::msg::Vector3 constructRPY(double roll = 0, double pitch = 0, double yaw = 0);
98 
105 geometry_msgs::msg::Vector3 constructRPYfromQuaternion(geometry_msgs::msg::Quaternion quaternion);
106 
119  double x, double y, double z, double roll, double pitch, double yaw);
120 
127 template <typename T>
128 std::vector<T> getUniqueValues(const std::vector<T> & input_vector)
129 {
130  std::vector<T> output_vector(input_vector);
131 
132  std::unordered_set<T> unique_values;
133  auto empty_elements_start = std::remove_if(
134  output_vector.begin(), output_vector.end(),
135  [&unique_values](T const & element) { return !unique_values.insert(element).second; });
136  output_vector.erase(empty_elements_start, output_vector.end());
137 
138  return output_vector;
139 }
140 
141 enum class LidarType { VLP16, VLP32 };
142 
143 const simulation_api_schema::LidarConfiguration constructLidarConfiguration(
144  const LidarType type, const std::string & entity, const std::string & architecture_type,
145  const double lidar_sensor_delay = 0, const double horizontal_resolution = 1.0 / 180.0 * M_PI);
146 
147 const simulation_api_schema::DetectionSensorConfiguration constructDetectionSensorConfiguration(
148  const std::string & entity, const std::string & architecture_type, const double update_duration,
149  const double range = 300.0, const bool detect_all_objects_in_range = false,
150  const double pos_noise_stddev = 0, const int random_seed = 0,
151  const double probability_of_lost = 0, const double object_recognition_delay = 0,
152  const double object_recognition_ground_truth_delay = 0);
153 } // namespace helper
154 } // namespace traffic_simulator
155 
156 std::ostream & operator<<(
157  std::ostream & os, const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose);
158 
159 std::ostream & operator<<(std::ostream & os, const geometry_msgs::msg::Point & point);
160 
161 std::ostream & operator<<(std::ostream & os, const geometry_msgs::msg::Vector3 & vector);
162 
163 std::ostream & operator<<(std::ostream & os, const geometry_msgs::msg::Quaternion & quat);
164 
165 std::ostream & operator<<(std::ostream & os, const geometry_msgs::msg::Pose & pose);
166 
167 template <typename T>
168 auto operator+(const std::vector<T> & v0, const std::vector<T> & v1) -> decltype(auto)
169 {
170  auto result = v0;
171  result.reserve(v0.size() + v1.size());
172  result.insert(result.end(), v1.begin(), v1.end());
173  return result;
174 }
175 
176 template <typename T>
177 auto operator+=(std::vector<T> & v0, const std::vector<T> & v1) -> decltype(auto)
178 {
179  v0.reserve(v0.size() + v1.size());
180  v0.insert(v0.end(), v1.begin(), v1.end());
181  return v0;
182 }
183 
184 template <typename T>
185 auto sortAndUnique(const std::vector<T> & data) -> std::vector<T>
186 {
187  std::vector<T> ret = data;
188  std::sort(ret.begin(), ret.end());
189  ret.erase(std::unique(ret.begin(), ret.end()), ret.end());
190  return ret;
191 }
192 
193 #endif // TRAFFIC_SIMULATOR__HELPER__HELPER_HPP_
auto operator+(const std::vector< T > &v0, const std::vector< T > &v1) -> decltype(auto)
Definition: helper.hpp:168
auto operator+=(std::vector< T > &v0, const std::vector< T > &v1) -> decltype(auto)
Definition: helper.hpp:177
auto sortAndUnique(const std::vector< T > &data) -> std::vector< T >
Definition: helper.hpp:185
std::ostream & operator<<(std::ostream &os, const traffic_simulator_msgs::msg::LaneletPose &lanelet_pose)
Definition: helper.cpp:190
geometry_msgs::msg::Vector3 constructRPY(double roll=0, double pitch=0, double yaw=0)
helper function for constructing rpy
Definition: helper.cpp:75
auto constructCanonicalizedLaneletPose(lanelet::Id lanelet_id, double s, double offset) -> CanonicalizedLaneletPose
helper function for constructing canonicalized lanelet pose
Definition: helper.cpp:69
geometry_msgs::msg::Pose constructPose(double x, double y, double z, double roll, double pitch, double yaw)
helper function for constructing pose
Definition: helper.cpp:89
const simulation_api_schema::LidarConfiguration constructLidarConfiguration(const LidarType type, const std::string &entity, const std::string &architecture_type, const double lidar_sensor_delay=0, const double horizontal_resolution=1.0/180.0 *M_PI)
Definition: helper.cpp:120
std::vector< T > getUniqueValues(const std::vector< T > &input_vector)
helper function for creating vector without duplicates, with preserved order
Definition: helper.hpp:128
const simulation_api_schema::DetectionSensorConfiguration constructDetectionSensorConfiguration(const std::string &entity, const std::string &architecture_type, const double update_duration, const double range=300.0, const bool detect_all_objects_in_range=false, const double pos_noise_stddev=0, const int random_seed=0, const double probability_of_lost=0, const double object_recognition_delay=0, const double object_recognition_ground_truth_delay=0)
Definition: helper.cpp:100
geometry_msgs::msg::Vector3 constructRPYfromQuaternion(geometry_msgs::msg::Quaternion quaternion)
helper function for constructing rpy
Definition: helper.cpp:84
traffic_simulator_msgs::msg::ActionStatus constructActionStatus(double linear_vel=0, double angular_vel=0, double linear_accel=0, double angular_accel=0)
helper function for constructing action status
Definition: helper.cpp:25
LidarType
Definition: helper.hpp:141
LaneletPose constructLaneletPose(lanelet::Id lanelet_id, double s, double offset=0, double roll=0, double pitch=0, double yaw=0)
helper function for constructing lanelet pose
Definition: helper.cpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:64
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:68
Definition: api.hpp:48
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
std::string string
Definition: junit5.hpp:26
traffic_simulator::lanelet_pose::CanonicalizedLaneletPose CanonicalizedLaneletPose
Definition: test_lanelet_pose.cpp:21