scenario_simulator_v2 C++ API
Public Member Functions | List of all members
traffic_simulator::entity::MiscObjectEntity Class Reference

#include <misc_object_entity.hpp>

Inheritance diagram for traffic_simulator::entity::MiscObjectEntity:
Inheritance graph
[legend]
Collaboration diagram for traffic_simulator::entity::MiscObjectEntity:
Collaboration graph
[legend]

Public Member Functions

 MiscObjectEntity (const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &, const traffic_simulator_msgs::msg::MiscObjectParameters &)
 
void onUpdate (double, double) override
 
auto getCurrentAction () const -> std::string override
 
auto getDefaultDynamicConstraints () const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
 
auto getEntityType () const -> const traffic_simulator_msgs::msg::EntityType &override
 
auto getEntityTypename () const -> const std::string &override
 
 ~MiscObjectEntity () override=default
 
auto getGoalPoses () -> std::vector< CanonicalizedLaneletPose > override
 
std::optional< traffic_simulator_msgs::msg::Obstacle > getObstacle () override
 
auto getRouteLanelets (double) -> lanelet::Ids override
 
auto fillLaneletPose (CanonicalizedEntityStatus &) -> void override
 
auto getWaypoints () -> const traffic_simulator_msgs::msg::WaypointsArray override
 
void requestSpeedChange (double, bool) override
 
void requestSpeedChange (const speed_change::RelativeTargetSpeed &, bool) override
 
void requestAssignRoute (const std::vector< CanonicalizedLaneletPose > &) override
 
void requestAssignRoute (const std::vector< geometry_msgs::msg::Pose > &) override
 
void requestAcquirePosition (const CanonicalizedLaneletPose &) override
 
void requestAcquirePosition (const geometry_msgs::msg::Pose &) override
 
void requestSpeedChange (const double, const speed_change::Transition, const speed_change::Constraint, const bool) override
 
auto getBehaviorParameter () const -> traffic_simulator_msgs::msg::BehaviorParameter override
 
void setBehaviorParameter (const traffic_simulator_msgs::msg::BehaviorParameter &) override
 
void setVelocityLimit (double) override
 
void setAccelerationLimit (double) override
 
void setAccelerationRateLimit (double) override
 
void setDecelerationLimit (double) override
 
void setDecelerationRateLimit (double) override
 
auto getMaxAcceleration () const -> double override
 
auto getMaxDeceleration () const -> double override
 
- Public Member Functions inherited from traffic_simulator::entity::EntityBase
 EntityBase (const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &)
 
virtual ~EntityBase ()=default
 
virtual void appendDebugMarker (visualization_msgs::msg::MarkerArray &)
 
virtual auto asFieldOperatorApplication () const -> concealer::FieldOperatorApplication &
 
virtual void cancelRequest ()
 
auto getBoundingBox () const noexcept -> traffic_simulator_msgs::msg::BoundingBox
 Get BoundingBox of the entity. More...
 
auto getCurrentAccel () const noexcept -> geometry_msgs::msg::Accel
 Get CurrentAccel of the entity. More...
 
auto getCurrentTwist () const noexcept -> geometry_msgs::msg::Twist
 Get CurrentTwist of the entity. More...
 
auto getDynamicConstraints () const noexcept -> traffic_simulator_msgs::msg::DynamicConstraints
 Get DynamicConstraints of the entity. More...
 
auto getEntityStatusBeforeUpdate () const noexcept -> const CanonicalizedEntityStatus &
 Get EntityStatusBeforeUpdate of the entity. More...
 
auto getEntitySubtype () const noexcept -> traffic_simulator_msgs::msg::EntitySubtype
 Get EntitySubtype of the entity. More...
 
auto getLinearJerk () const noexcept -> double
 Get LinearJerk of the entity. More...
 
auto getMapPose () const noexcept -> geometry_msgs::msg::Pose
 Get MapPose of the entity. More...
 
auto getStandStillDuration () const noexcept -> double
 Get StandStillDuration of the entity. More...
 
auto getStatus () const noexcept -> const CanonicalizedEntityStatus &
 Get Status of the entity. More...
 
auto getTraveledDistance () const noexcept -> double
 Get TraveledDistance of the entity. More...
 
auto isNpcLogicStarted () const -> bool
 
auto laneMatchingSucceed () const -> bool
 
auto get2DPolygon () const -> std::vector< geometry_msgs::msg::Point >
 
auto getLaneletPose () const -> std::optional< CanonicalizedLaneletPose >
 
auto getLaneletPose (double matching_distance) const -> std::optional< CanonicalizedLaneletPose >
 
auto getMapPoseFromRelativePose (const geometry_msgs::msg::Pose &) const -> geometry_msgs::msg::Pose
 
virtual auto getDefaultMatchingDistanceForLaneletPoseCalculation () const -> double
 
virtual void onPostUpdate (double current_time, double step_time)
 
void resetDynamicConstraints ()
 
virtual void requestLaneChange (const lanelet::Id)
 
virtual void requestLaneChange (const traffic_simulator::lane_change::Parameter &)
 
void requestLaneChange (const lane_change::AbsoluteTarget &, const lane_change::TrajectoryShape, const lane_change::Constraint &)
 
void requestLaneChange (const lane_change::RelativeTarget &, const lane_change::TrajectoryShape, const lane_change::Constraint &)
 
virtual void requestSpeedChange (const speed_change::RelativeTargetSpeed &, const speed_change::Transition, const speed_change::Constraint, const bool)
 
virtual void requestClearRoute ()
 
virtual auto isControlledBySimulator () const -> bool
 
virtual auto setControlledBySimulator (bool) -> void
 
virtual auto requestFollowTrajectory (const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void
 
virtual void requestWalkStraight ()
 
void setDynamicConstraints (const traffic_simulator_msgs::msg::DynamicConstraints &)
 
void setOtherStatus (const std::unordered_map< std::string, CanonicalizedEntityStatus > &)
 
virtual auto setStatus (const CanonicalizedEntityStatus &) -> void
 
virtual auto setLinearAcceleration (const double linear_acceleration) -> void
 
virtual auto setLinearVelocity (const double linear_velocity) -> void
 
virtual void setTrafficLightManager (const std::shared_ptr< traffic_simulator::TrafficLightManager > &)
 
virtual auto activateOutOfRangeJob (double min_velocity, double max_velocity, double min_acceleration, double max_acceleration, double min_jerk, double max_jerk) -> void
 
virtual auto setMapPose (const geometry_msgs::msg::Pose &map_pose) -> void
 
auto setTwist (const geometry_msgs::msg::Twist &twist) -> void
 
auto setAcceleration (const geometry_msgs::msg::Accel &accel) -> void
 
auto setLinearJerk (const double liner_jerk) -> void
 
virtual void startNpcLogic (const double current_time)
 
void stopAtCurrentPosition ()
 
void updateEntityStatusTimestamp (const double current_time)
 
auto updateStandStillDuration (const double step_time) -> double
 
auto updateTraveledDistance (const double step_time) -> double
 
bool reachPosition (const geometry_msgs::msg::Pose &target_pose, const double tolerance) const
 
bool reachPosition (const CanonicalizedLaneletPose &lanelet_pose, const double tolerance) const
 
bool reachPosition (const std::string &target_name, const double tolerance) const
 
auto requestSynchronize (const std::string &target_name, const CanonicalizedLaneletPose &target_sync_pose, const CanonicalizedLaneletPose &entity_target, const double target_speed, const double tolerance) -> bool
 
virtual auto fillLaneletPose (CanonicalizedEntityStatus &status, bool include_crosswalk) -> void final
 

Additional Inherited Members

- Public Attributes inherited from traffic_simulator::entity::EntityBase
const std::string name
 
bool verbose
 
- Protected Attributes inherited from traffic_simulator::entity::EntityBase
CanonicalizedEntityStatus status_
 
CanonicalizedEntityStatus status_before_update_
 
std::shared_ptr< hdmap_utils::HdMapUtilshdmap_utils_ptr_
 
std::shared_ptr< traffic_simulator::TrafficLightManagertraffic_light_manager_
 
bool npc_logic_started_ = false
 
double stand_still_duration_ = 0.0
 
double traveled_distance_ = 0.0
 
double prev_job_duration_ = 0.0
 
double step_time_ = 0.0
 
std::unordered_map< std::string, CanonicalizedEntityStatusother_status_
 
std::optional< double > target_speed_
 
traffic_simulator::job::JobList job_list_
 
std::unique_ptr< traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlannerspeed_planner_
 

Constructor & Destructor Documentation

◆ MiscObjectEntity()

traffic_simulator::entity::MiscObjectEntity::MiscObjectEntity ( const std::string &  name,
const CanonicalizedEntityStatus entity_status,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr,
const traffic_simulator_msgs::msg::MiscObjectParameters &   
)
explicit

◆ ~MiscObjectEntity()

traffic_simulator::entity::MiscObjectEntity::~MiscObjectEntity ( )
overridedefault

Member Function Documentation

◆ fillLaneletPose()

auto traffic_simulator::entity::MiscObjectEntity::fillLaneletPose ( CanonicalizedEntityStatus status) -> void
overridevirtual

◆ getBehaviorParameter()

auto traffic_simulator::entity::MiscObjectEntity::getBehaviorParameter ( ) const -> traffic_simulator_msgs::msg::BehaviorParameter
overridevirtual

◆ getCurrentAction()

auto traffic_simulator::entity::MiscObjectEntity::getCurrentAction ( ) const -> std::string
overridevirtual

◆ getDefaultDynamicConstraints()

auto traffic_simulator::entity::MiscObjectEntity::getDefaultDynamicConstraints ( ) const -> const traffic_simulator_msgs::msg::DynamicConstraints &
overridevirtual

◆ getEntityType()

auto traffic_simulator::entity::MiscObjectEntity::getEntityType ( ) const -> const traffic_simulator_msgs::msg::EntityType &
inlineoverridevirtual

◆ getEntityTypename()

auto traffic_simulator::entity::MiscObjectEntity::getEntityTypename ( ) const -> const std::string &
inlineoverridevirtual

◆ getGoalPoses()

auto traffic_simulator::entity::MiscObjectEntity::getGoalPoses ( ) -> std::vector<CanonicalizedLaneletPose>
inlineoverridevirtual

◆ getMaxAcceleration()

auto traffic_simulator::entity::MiscObjectEntity::getMaxAcceleration ( ) const -> double
inlineoverridevirtual

◆ getMaxDeceleration()

auto traffic_simulator::entity::MiscObjectEntity::getMaxDeceleration ( ) const -> double
inlineoverridevirtual

◆ getObstacle()

std::optional<traffic_simulator_msgs::msg::Obstacle> traffic_simulator::entity::MiscObjectEntity::getObstacle ( )
inlineoverridevirtual

◆ getRouteLanelets()

auto traffic_simulator::entity::MiscObjectEntity::getRouteLanelets ( double  ) -> lanelet::Ids
inlineoverridevirtual

◆ getWaypoints()

auto traffic_simulator::entity::MiscObjectEntity::getWaypoints ( ) -> const traffic_simulator_msgs::msg::WaypointsArray
inlineoverridevirtual

◆ onUpdate()

void traffic_simulator::entity::MiscObjectEntity::onUpdate ( double  ,
double  step_time 
)
overridevirtual

◆ requestAcquirePosition() [1/2]

void traffic_simulator::entity::MiscObjectEntity::requestAcquirePosition ( const CanonicalizedLaneletPose )
inlineoverridevirtual

◆ requestAcquirePosition() [2/2]

void traffic_simulator::entity::MiscObjectEntity::requestAcquirePosition ( const geometry_msgs::msg::Pose &  )
inlineoverridevirtual

◆ requestAssignRoute() [1/2]

void traffic_simulator::entity::MiscObjectEntity::requestAssignRoute ( const std::vector< CanonicalizedLaneletPose > &  )
inlineoverridevirtual

◆ requestAssignRoute() [2/2]

void traffic_simulator::entity::MiscObjectEntity::requestAssignRoute ( const std::vector< geometry_msgs::msg::Pose > &  )
inlineoverridevirtual

◆ requestSpeedChange() [1/3]

void traffic_simulator::entity::MiscObjectEntity::requestSpeedChange ( const double  ,
const speed_change::Transition  ,
const speed_change::Constraint  ,
const bool   
)
overridevirtual

◆ requestSpeedChange() [2/3]

void traffic_simulator::entity::MiscObjectEntity::requestSpeedChange ( const speed_change::RelativeTargetSpeed ,
bool   
)
overridevirtual

◆ requestSpeedChange() [3/3]

void traffic_simulator::entity::MiscObjectEntity::requestSpeedChange ( double  ,
bool   
)
overridevirtual

◆ setAccelerationLimit()

void traffic_simulator::entity::MiscObjectEntity::setAccelerationLimit ( double  )
inlineoverridevirtual

◆ setAccelerationRateLimit()

void traffic_simulator::entity::MiscObjectEntity::setAccelerationRateLimit ( double  )
inlineoverridevirtual

◆ setBehaviorParameter()

void traffic_simulator::entity::MiscObjectEntity::setBehaviorParameter ( const traffic_simulator_msgs::msg::BehaviorParameter &  )
overridevirtual

◆ setDecelerationLimit()

void traffic_simulator::entity::MiscObjectEntity::setDecelerationLimit ( double  )
inlineoverridevirtual

◆ setDecelerationRateLimit()

void traffic_simulator::entity::MiscObjectEntity::setDecelerationRateLimit ( double  )
inlineoverridevirtual

◆ setVelocityLimit()

void traffic_simulator::entity::MiscObjectEntity::setVelocityLimit ( double  )
inlineoverridevirtual

The documentation for this class was generated from the following files: