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)
44 auto set(
const EntityStatus & status,
const double matching_distance) -> void;
47 auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &;
49 auto
getTime() const noexcept ->
double;
52 auto
getMapPose() const noexcept -> const geometry_msgs::msg::
Pose &;
57 auto
getTwist() const noexcept -> const geometry_msgs::msg::Twist &;
58 auto
setTwist(const geometry_msgs::msg::Twist & twist) ->
void;
61 auto
getAccel() const noexcept -> const geometry_msgs::msg::Accel &;
62 auto
setAccel(const geometry_msgs::msg::Accel & accel) ->
void;
74 auto
getName() const noexcept -> const
std::
string & {
return entity_status_.name; }
Definition: entity_status.hpp:32
auto set(const CanonicalizedEntityStatus &status) -> void
Definition: entity_status.cpp:55
CanonicalizedEntityStatus(const EntityStatus &may_non_canonicalized_entity_status, const std::optional< CanonicalizedLaneletPose > &canonicalized_lanelet_pose)
Definition: entity_status.cpp:22
auto getLaneletIds() const -> lanelet::Ids
Definition: entity_status.cpp:142
auto getAccel() const noexcept -> const geometry_msgs::msg::Accel &
Definition: entity_status.cpp:178
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:168
auto setLinearJerk(double) -> void
Definition: entity_status.cpp:183
auto getCanonicalizedLaneletPose() const noexcept -> const std::optional< CanonicalizedLaneletPose > &
Definition: entity_status.cpp:147
auto getTwist() const noexcept -> const geometry_msgs::msg::Twist &
Definition: entity_status.cpp:158
auto getLinearJerk() const noexcept -> double
Definition: entity_status.cpp:188
auto isInLanelet() const noexcept -> bool
Definition: entity_status.cpp:101
auto setTime(double) -> void
Definition: entity_status.cpp:193
auto getLaneletId() const -> lanelet::Id
Definition: entity_status.cpp:137
auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &
Definition: entity_status.cpp:95
auto getBoundingBox() const noexcept -> const traffic_simulator_msgs::msg::BoundingBox &
Definition: entity_status.cpp:106
auto getName() const noexcept -> const std::string &
Definition: entity_status.hpp:74
auto getAltitude() const -> double
Definition: entity_status.cpp:122
auto getTime() const noexcept -> double
Definition: entity_status.cpp:195
auto setLinearAcceleration(double linear_acceleration) -> void
Definition: entity_status.cpp:173
auto setAction(const std::string &action) -> void
Definition: entity_status.cpp:90
auto setTwist(const geometry_msgs::msg::Twist &twist) -> void
Definition: entity_status.cpp:153
auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &
Definition: entity_status.cpp:117
auto setLinearVelocity(double linear_velocity) -> void
Definition: entity_status.cpp:163
auto getLaneletPose() const -> const LaneletPose &
Definition: entity_status.cpp:128
auto setMapPose(const geometry_msgs::msg::Pose &pose) -> void
Definition: entity_status.cpp:112
Definition: lanelet_pose.hpp:35
Definition: lanelet_wrapper.hpp:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:61
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:30
auto isSameLaneletId(const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
Definition: entity_status.cpp:198
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