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 auto makePoint(const double x, const double y, const double z = 0.0) -> geometry_msgs::msg::Point
30 {
31  return geometry_msgs::build<geometry_msgs::msg::Point>().x(x).y(y).z(z);
32 }
33 
34 auto makeBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg::BoundingBox
35 {
36  return traffic_simulator_msgs::build<traffic_simulator_msgs::msg::BoundingBox>()
37  .center(makePoint(1.0, center_y))
38  .dimensions(geometry_msgs::build<geometry_msgs::msg::Vector3>().x(4.0).y(2.0).z(1.5));
39 }
40 
41 auto makeSmallBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg::BoundingBox
42 {
43  return traffic_simulator_msgs::build<traffic_simulator_msgs::msg::BoundingBox>()
44  .center(makePoint(0.0, center_y))
45  .dimensions(geometry_msgs::build<geometry_msgs::msg::Vector3>().x(1.0).y(1.0).z(1.0));
46 }
47 
48 auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion
49 {
51  geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0.0).y(0.0).z(yaw));
52 }
53 
54 auto makePose(
55  geometry_msgs::msg::Point position,
56  geometry_msgs::msg::Quaternion orientation = geometry_msgs::msg::Quaternion())
57  -> geometry_msgs::msg::Pose
58 {
59  return geometry_msgs::build<geometry_msgs::msg::Pose>().position(position).orientation(
60  orientation);
61 }
62 
63 auto makeHdMapUtilsSharedPointer() -> std::shared_ptr<hdmap_utils::HdMapUtils>
64 {
65  return std::make_shared<hdmap_utils::HdMapUtils>(
66  ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm",
67  geographic_msgs::build<geographic_msgs::msg::GeoPoint>()
68  .latitude(35.9037067912303)
69  .longitude(139.9337945139059)
70  .altitude(0.0));
71 }
72 
74  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils, const lanelet::Id id = 120659,
75  const double s = 0.0, const double offset = 0.0)
77 {
80 }
81 
83  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils,
85  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
86  const std::string name = "default_entity_name",
87  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
89 {
90  return traffic_simulator_msgs::build<traffic_simulator::EntityStatus>()
91  .type(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntityType>().type(type))
92  .subtype(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntitySubtype>().value(
93  traffic_simulator_msgs::msg::EntitySubtype::UNKNOWN))
94  .time(0.0)
95  .name(name)
96  .bounding_box(bbox)
97  .action_status(traffic_simulator::helper::constructActionStatus(speed, 0.0, 0.0, 0.0))
98  .pose(hdmap_utils->toMapPose(static_cast<traffic_simulator::LaneletPose>(pose)).pose)
99  .lanelet_pose(static_cast<traffic_simulator::LaneletPose>(pose))
100  .lanelet_pose_valid(true);
101 }
102 
104  std::shared_ptr<hdmap_utils::HdMapUtils> /* hdmap_utils */, geometry_msgs::msg::Pose pose,
105  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
106  const std::string name = "default_entity_name",
107  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
109 {
110  return traffic_simulator_msgs::build<traffic_simulator::EntityStatus>()
111  .type(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntityType>().type(type))
112  .subtype(traffic_simulator_msgs::build<traffic_simulator_msgs::msg::EntitySubtype>().value(
113  traffic_simulator_msgs::msg::EntitySubtype::UNKNOWN))
114  .time(0.0)
115  .name(name)
116  .bounding_box(bbox)
117  .action_status(traffic_simulator::helper::constructActionStatus(speed, 0.0, 0.0, 0.0))
118  .pose(pose)
120  .lanelet_pose_valid(false);
121 }
122 
124  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils,
126  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
127  const std::string name = "default_entity_name",
128  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
130 {
132  makeEntityStatus(hdmap_utils, pose, bbox, speed, name, type), hdmap_utils);
133 }
134 
136  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils, geometry_msgs::msg::Pose pose,
137  traffic_simulator_msgs::msg::BoundingBox bbox, const double speed = 0.0,
138  const std::string name = "default_entity_name",
139  const uint8_t type = traffic_simulator_msgs::msg::EntityType::VEHICLE)
141 {
143  makeEntityStatus(hdmap_utils, pose, bbox, speed, name, type), hdmap_utils);
144 }
145 
146 #endif // TRAFFIC_SIMULATOR__TEST__ENTITY_HELPER_FUNCTIONS_HPP_
auto makeSmallBoundingBox(const double center_y=0.0) -> traffic_simulator_msgs::msg::BoundingBox
Definition: helper_functions.hpp:41
auto makeHdMapUtilsSharedPointer() -> std::shared_ptr< hdmap_utils::HdMapUtils >
Definition: helper_functions.hpp:63
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:82
auto makeCanonicalizedEntityStatus(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::entity_status::CanonicalizedEntityStatus
Definition: helper_functions.hpp:123
auto makeBoundingBox(const double center_y=0.0) -> traffic_simulator_msgs::msg::BoundingBox
Definition: helper_functions.hpp:34
auto makePoint(const double x, const double y, const double z=0.0) -> geometry_msgs::msg::Point
Definition: helper_functions.hpp:29
auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion
Definition: helper_functions.hpp:48
auto makePose(geometry_msgs::msg::Point position, geometry_msgs::msg::Quaternion orientation=geometry_msgs::msg::Quaternion()) -> geometry_msgs::msg::Pose
Definition: helper_functions.hpp:54
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:73
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:24
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:39
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:24
std::string string
Definition: junit5.hpp:26