scenario_simulator_v2 C++ API
helper_functions.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__TEST__HELPER_FUNCTIONS_HPP_
16 #define TRAFFIC_SIMULATOR__TEST__HELPER_FUNCTIONS_HPP_
17 
18 #include <ament_index_cpp/get_package_share_directory.hpp>
23 #include <traffic_simulator_msgs/msg/entity_subtype.hpp>
24 #include <traffic_simulator_msgs/msg/entity_type.hpp>
25 
26 #include "catalogs.hpp"
27 #include "expect_eq_macros.hpp"
28 
29 constexpr auto convertDegToRad(const double deg) -> double { return deg / 180.0 * M_PI; }
30 constexpr auto convertRadToDeg(const double rad) -> double { return rad * 180.0 / M_PI; }
31 
32 auto makePoint(const double x, const double y, const double z = 0.0) -> geometry_msgs::msg::Point
33 {
34  return geometry_msgs::build<geometry_msgs::msg::Point>().x(x).y(y).z(z);
35 }
36 
37 auto makeBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg::BoundingBox
38 {
39  return traffic_simulator_msgs::build<traffic_simulator_msgs::msg::BoundingBox>()
40  .center(makePoint(1.0, center_y))
41  .dimensions(geometry_msgs::build<geometry_msgs::msg::Vector3>().x(4.0).y(2.0).z(1.5));
42 }
43 
45  const double x, const double y, const double x_offset = 0.0, const double y_offset = 0.0)
46  -> traffic_simulator_msgs::msg::BoundingBox
47 {
48  return traffic_simulator_msgs::build<traffic_simulator_msgs::msg::BoundingBox>()
49  .center(geometry_msgs::build<geometry_msgs::msg::Point>().x(x_offset).y(y_offset).z(0.0))
50  .dimensions(geometry_msgs::build<geometry_msgs::msg::Vector3>().x(x).y(y).z(0.0));
51 }
52 
53 auto makeSmallBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg::BoundingBox
54 {
55  return traffic_simulator_msgs::build<traffic_simulator_msgs::msg::BoundingBox>()
56  .center(makePoint(0.0, center_y))
57  .dimensions(geometry_msgs::build<geometry_msgs::msg::Vector3>().x(1.0).y(1.0).z(1.0));
58 }
59 
60 auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion
61 {
63  geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0.0).y(0.0).z(yaw));
64 }
65 
66 auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose
67 {
71  return geometry_msgs::build<geometry_msgs::msg::Pose>()
72  .position(geometry_msgs::build<geometry_msgs::msg::Point>().x(x).y(y).z(0.0))
74  geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0.0).y(0.0).z(
75  convertDegToRad(yaw_deg))));
76 }
77 
78 auto makePose(
79  geometry_msgs::msg::Point position,
80  geometry_msgs::msg::Quaternion orientation = geometry_msgs::msg::Quaternion())
81  -> geometry_msgs::msg::Pose
82 {
83  return geometry_msgs::build<geometry_msgs::msg::Pose>().position(position).orientation(
84  orientation);
85 }
86 
87 auto makeHdMapUtilsSharedPointer() -> std::shared_ptr<hdmap_utils::HdMapUtils>
88 {
89  return std::make_shared<hdmap_utils::HdMapUtils>(
90  ament_index_cpp::get_package_share_directory("traffic_simulator") +
91  "/map/standard_map/lanelet2_map.osm",
92  geographic_msgs::build<geographic_msgs::msg::GeoPoint>()
93  .latitude(35.9037067912303)
94  .longitude(139.9337945139059)
95  .altitude(0.0));
96 }
97 
99  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils, const lanelet::Id id = 120659,
100  const double s = 0.0, const double offset = 0.0)
102 {
105 }
106 
108  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils,
110  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
111  const std::string name = "default_entity_name",
112  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
114 {
115  return traffic_simulator_msgs::build<traffic_simulator::EntityStatus>()
116  .type(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntityType>().type(type))
117  .subtype(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntitySubtype>().value(
118  traffic_simulator_msgs::msg::EntitySubtype::UNKNOWN))
119  .time(0.0)
120  .name(name)
121  .bounding_box(bbox)
122  .action_status(traffic_simulator::helper::constructActionStatus(speed, 0.0, 0.0, 0.0))
123  .pose(hdmap_utils->toMapPose(static_cast<traffic_simulator::LaneletPose>(pose)).pose)
124  .lanelet_pose(static_cast<traffic_simulator::LaneletPose>(pose))
125  .lanelet_pose_valid(true);
126 }
127 
129  std::shared_ptr<hdmap_utils::HdMapUtils> /* hdmap_utils */, geometry_msgs::msg::Pose pose,
130  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
131  const std::string name = "default_entity_name",
132  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
134 {
135  return traffic_simulator_msgs::build<traffic_simulator::EntityStatus>()
136  .type(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntityType>().type(type))
137  .subtype(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntitySubtype>().value(
138  traffic_simulator_msgs::msg::EntitySubtype::UNKNOWN))
139  .time(0.0)
140  .name(name)
141  .bounding_box(bbox)
142  .action_status(traffic_simulator::helper::constructActionStatus(speed, 0.0, 0.0, 0.0))
143  .pose(pose)
145  .lanelet_pose_valid(false);
146 }
147 
149  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils,
151  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
152  const std::string name = "default_entity_name",
153  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
155 {
157  makeEntityStatus(hdmap_utils, canonicalized_lanelet_pose, bbox, speed, name, type),
158  canonicalized_lanelet_pose);
159 }
160 
162  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils, geometry_msgs::msg::Pose pose,
163  traffic_simulator_msgs::msg::BoundingBox bbox, const double matching_distance = 1.0,
164  const double speed = 0.0, const std::string name = "default_entity_name",
165  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
167 {
168  const auto include_crosswalk =
169  (traffic_simulator_msgs::msg::EntityType::PEDESTRIAN == type ||
170  traffic_simulator_msgs::msg::EntityType::MISC_OBJECT == type);
171  const auto canonicalized_lanelet_pose = traffic_simulator::pose::toCanonicalizedLaneletPose(
172  pose, bbox, include_crosswalk, matching_distance, hdmap_utils);
174  makeEntityStatus(hdmap_utils, pose, bbox, speed, name, type), canonicalized_lanelet_pose);
175 }
176 
177 #endif // TRAFFIC_SIMULATOR__TEST__ENTITY_HELPER_FUNCTIONS_HPP_
Definition: cache.hpp:46
auto convertEulerAngleToQuaternion(const T &v)
Definition: euler_to_quaternion.hpp:30
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
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
auto toCanonicalizedLaneletPose(const geometry_msgs::msg::Pose &map_pose, const bool include_crosswalk, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< CanonicalizedLaneletPose >
Definition: pose.cpp:73
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26
traffic_simulator::lanelet_pose::CanonicalizedLaneletPose CanonicalizedLaneletPose
Definition: test_lanelet_pose.cpp:21
auto makeSmallBoundingBox(const double center_y=0.0) -> traffic_simulator_msgs::msg::BoundingBox
Definition: helper_functions.hpp:53
auto makeHdMapUtilsSharedPointer() -> std::shared_ptr< hdmap_utils::HdMapUtils >
Definition: helper_functions.hpp:87
auto makeEntityStatus(std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils, traffic_simulator::lanelet_pose::CanonicalizedLaneletPose pose, traffic_simulator_msgs::msg::BoundingBox bbox, const double speed=0.0, const std::string name="default_entity_name", const uint8_t type=traffic_simulator_msgs::msg::EntityType::VEHICLE) -> traffic_simulator::EntityStatus
Definition: helper_functions.hpp:107
auto makeBoundingBox(const double center_y=0.0) -> traffic_simulator_msgs::msg::BoundingBox
Definition: helper_functions.hpp:37
auto makePoint(const double x, const double y, const double z=0.0) -> geometry_msgs::msg::Point
Definition: helper_functions.hpp:32
auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion
Definition: helper_functions.hpp:60
auto makeCanonicalizedEntityStatus(std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils, traffic_simulator::lanelet_pose::CanonicalizedLaneletPose canonicalized_lanelet_pose, traffic_simulator_msgs::msg::BoundingBox bbox, const double speed=0.0, const std::string name="default_entity_name", const uint8_t type=traffic_simulator_msgs::msg::EntityType::VEHICLE) -> traffic_simulator::entity_status::CanonicalizedEntityStatus
Definition: helper_functions.hpp:148
auto makeCustom2DBoundingBox(const double x, const double y, const double x_offset=0.0, const double y_offset=0.0) -> traffic_simulator_msgs::msg::BoundingBox
Definition: helper_functions.hpp:44
auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose
Definition: helper_functions.hpp:66
constexpr auto convertDegToRad(const double deg) -> double
Definition: helper_functions.hpp:29
auto makeCanonicalizedLaneletPose(std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils, const lanelet::Id id=120659, const double s=0.0, const double offset=0.0) -> traffic_simulator::lanelet_pose::CanonicalizedLaneletPose
Definition: helper_functions.hpp:98
constexpr auto convertRadToDeg(const double rad) -> double
Definition: helper_functions.hpp:30