scenario_simulator_v2 C++ API
entity_status.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__DATA_TYPE__ENTITY_STATUS_HPP_
16 #define TRAFFIC_SIMULATOR__DATA_TYPE__ENTITY_STATUS_HPP_
17 
21 #include <traffic_simulator_msgs/msg/entity_status.hpp>
22 
23 namespace traffic_simulator
24 {
28 
29 inline namespace entity_status
30 {
32 {
33 public:
35  const EntityStatus & may_non_canonicalized_entity_status,
36  const std::optional<CanonicalizedLaneletPose> & canonicalized_lanelet_pose);
38  explicit operator EntityStatus() const noexcept { return entity_status_; }
39 
40  auto set(const CanonicalizedEntityStatus & status) -> void;
41  auto set(
42  const EntityStatus & status, const lanelet::Ids & lanelet_ids, const double matching_distance,
43  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> void;
44  auto set(
45  const EntityStatus & status, const double matching_distance,
46  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> void;
47 
48  auto setAction(const std::string & action) -> void;
49  auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &;
50 
51  auto getTime() const noexcept -> double;
52  auto setTime(double) -> void;
53 
54  auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &;
55  auto setMapPose(const geometry_msgs::msg::Pose & pose) -> void;
56 
57  auto getTwist() const noexcept -> const geometry_msgs::msg::Twist &;
58  auto setTwist(const geometry_msgs::msg::Twist & twist) -> void;
59  auto setLinearVelocity(double linear_velocity) -> void;
60 
61  auto getAccel() const noexcept -> const geometry_msgs::msg::Accel &;
62  auto setAccel(const geometry_msgs::msg::Accel & accel) -> void;
63  auto setLinearAcceleration(double linear_acceleration) -> void;
64 
65  auto getLinearJerk() const noexcept -> double;
66  auto setLinearJerk(double) -> void;
67 
68  auto laneMatchingSucceed() const noexcept -> bool;
69  auto getLaneletId() const noexcept -> lanelet::Id;
70  auto getLaneletIds() const noexcept -> lanelet::Ids;
71  auto getLaneletPose() const noexcept -> const LaneletPose &;
72  auto getCanonicalizedLaneletPose() const noexcept
73  -> const std::optional<CanonicalizedLaneletPose> &;
74  auto getName() const noexcept -> const std::string & { return entity_status_.name; }
75  auto getType() const noexcept -> const EntityType & { return entity_status_.type; }
76  auto getSubtype() const noexcept -> const EntitySubtype & { return entity_status_.subtype; }
77  auto getBoundingBox() const noexcept -> const traffic_simulator_msgs::msg::BoundingBox &;
78 
79 private:
80  std::optional<CanonicalizedLaneletPose> canonicalized_lanelet_pose_;
81  EntityStatus entity_status_;
82 };
83 } // namespace entity_status
84 auto isSameLaneletId(
85  const CanonicalizedEntityStatus & first_status, const CanonicalizedEntityStatus & second_status)
86  -> bool;
87 auto isSameLaneletId(const CanonicalizedEntityStatus & status, const lanelet::Id lanelet_id)
88  -> bool;
89 } // namespace traffic_simulator
90 
91 #endif // TRAFFIC_SIMULATOR__DATA_TYPE__ENTITY_STATUS_HPP_
Definition: entity_status.hpp:32
auto set(const CanonicalizedEntityStatus &status) -> void
Definition: entity_status.cpp:56
CanonicalizedEntityStatus(const EntityStatus &may_non_canonicalized_entity_status, const std::optional< CanonicalizedLaneletPose > &canonicalized_lanelet_pose)
Definition: entity_status.cpp:23
auto getLaneletIds() const noexcept -> lanelet::Ids
Definition: entity_status.cpp:139
auto getLaneletId() const noexcept -> lanelet::Id
Definition: entity_status.cpp:134
auto getAccel() const noexcept -> const geometry_msgs::msg::Accel &
Definition: entity_status.cpp:175
auto getSubtype() const noexcept -> const EntitySubtype &
Definition: entity_status.hpp:76
auto getType() const noexcept -> const EntityType &
Definition: entity_status.hpp:75
auto setAccel(const geometry_msgs::msg::Accel &accel) -> void
Definition: entity_status.cpp:165
auto setLinearJerk(double) -> void
Definition: entity_status.cpp:180
auto getCanonicalizedLaneletPose() const noexcept -> const std::optional< CanonicalizedLaneletPose > &
Definition: entity_status.cpp:144
auto getTwist() const noexcept -> const geometry_msgs::msg::Twist &
Definition: entity_status.cpp:155
auto getLinearJerk() const noexcept -> double
Definition: entity_status.cpp:185
auto setTime(double) -> void
Definition: entity_status.cpp:190
auto laneMatchingSucceed() const noexcept -> bool
Definition: entity_status.cpp:104
auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &
Definition: entity_status.cpp:98
auto getBoundingBox() const noexcept -> const traffic_simulator_msgs::msg::BoundingBox &
Definition: entity_status.cpp:109
auto getName() const noexcept -> const std::string &
Definition: entity_status.hpp:74
auto getTime() const noexcept -> double
Definition: entity_status.cpp:192
auto setLinearAcceleration(double linear_acceleration) -> void
Definition: entity_status.cpp:170
auto setAction(const std::string &action) -> void
Definition: entity_status.cpp:93
auto setTwist(const geometry_msgs::msg::Twist &twist) -> void
Definition: entity_status.cpp:150
auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &
Definition: entity_status.cpp:120
auto setLinearVelocity(double linear_velocity) -> void
Definition: entity_status.cpp:160
auto setMapPose(const geometry_msgs::msg::Pose &pose) -> void
Definition: entity_status.cpp:115
auto getLaneletPose() const noexcept -> const LaneletPose &
Definition: entity_status.cpp:125
Definition: lanelet_pose.hpp:27
Definition: cache.hpp:27
Definition: api.hpp:49
traffic_simulator_msgs::msg::EntityType EntityType
Definition: entity_status.hpp:26
traffic_simulator_msgs::msg::EntitySubtype EntitySubtype
Definition: entity_status.hpp:27
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
auto isSameLaneletId(const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
Definition: entity_status.cpp:195
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntitySubtype EntitySubtype
Definition: helper_functions.hpp:30
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32
traffic_simulator_msgs::EntityType EntityType
Definition: helper_functions.hpp:31