15 #ifndef TRAFFIC_SIMULATOR__DATA_TYPE__ENTITY_STATUS_HPP_
16 #define TRAFFIC_SIMULATOR__DATA_TYPE__ENTITY_STATUS_HPP_
21 #include <traffic_simulator_msgs/msg/entity_status.hpp>
29 inline namespace entity_status
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_; }
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;
45 const EntityStatus & status,
const double matching_distance,
46 const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> void;
49 auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &;
51 auto
getTime() const noexcept ->
double;
54 auto
getMapPose() const noexcept -> const geometry_msgs::msg::Pose &;
55 auto
setMapPose(const geometry_msgs::msg::Pose & pose) ->
void;
59 auto
getTwist() const noexcept -> const geometry_msgs::msg::Twist &;
60 auto
setTwist(const geometry_msgs::msg::Twist & twist) ->
void;
63 auto
getAccel() const noexcept -> const geometry_msgs::msg::Accel &;
64 auto
setAccel(const geometry_msgs::msg::Accel & accel) ->
void;
76 auto
getName() const noexcept -> const
std::
string & {
return entity_status_.name; }
79 auto getBoundingBox() const noexcept -> const traffic_simulator_msgs::msg::BoundingBox &;
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:144
auto getLaneletId() const noexcept -> lanelet::Id
Definition: entity_status.cpp:139
auto getAccel() const noexcept -> const geometry_msgs::msg::Accel &
Definition: entity_status.cpp:180
auto getSubtype() const noexcept -> const EntitySubtype &
Definition: entity_status.hpp:78
auto getType() const noexcept -> const EntityType &
Definition: entity_status.hpp:77
auto setAccel(const geometry_msgs::msg::Accel &accel) -> void
Definition: entity_status.cpp:170
auto setLinearJerk(double) -> void
Definition: entity_status.cpp:185
auto getCanonicalizedLaneletPose() const noexcept -> const std::optional< CanonicalizedLaneletPose > &
Definition: entity_status.cpp:149
auto getTwist() const noexcept -> const geometry_msgs::msg::Twist &
Definition: entity_status.cpp:160
auto getLinearJerk() const noexcept -> double
Definition: entity_status.cpp:190
auto setTime(double) -> void
Definition: entity_status.cpp:195
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:76
auto getAltitude() const -> double
Definition: entity_status.cpp:125
auto getTime() const noexcept -> double
Definition: entity_status.cpp:197
auto setLinearAcceleration(double linear_acceleration) -> void
Definition: entity_status.cpp:175
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:155
auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &
Definition: entity_status.cpp:120
auto setLinearVelocity(double linear_velocity) -> void
Definition: entity_status.cpp:165
auto setMapPose(const geometry_msgs::msg::Pose &pose) -> void
Definition: entity_status.cpp:115
auto getLaneletPose() const noexcept -> const LaneletPose &
Definition: entity_status.cpp:130
Definition: lanelet_pose.hpp:27
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:200
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