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

#include <vehicle_entity.hpp>

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

Classes

struct  BuiltinBehavior
 

Public Member Functions

 VehicleEntity (const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &, const traffic_simulator_msgs::msg::VehicleParameters &, const std::string &plugin_name=BuiltinBehavior::defaultBehavior())
 
 ~VehicleEntity () override=default
 
void appendDebugMarker (visualization_msgs::msg::MarkerArray &marker_array) override
 
void cancelRequest () override
 
auto getCurrentAction () const -> std::string override
 
auto getDefaultDynamicConstraints () const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
 
auto getDefaultMatchingDistanceForLaneletPoseCalculation () const -> double override
 
auto getBehaviorParameter () const -> traffic_simulator_msgs::msg::BehaviorParameter override
 
auto getMaxAcceleration () const -> double override
 
auto getMaxDeceleration () const -> double override
 
auto getEntityType () const -> const traffic_simulator_msgs::msg::EntityType &override
 
auto getEntityTypename () const -> const std::string &override
 
auto getGoalPoses () -> std::vector< CanonicalizedLaneletPose > override
 
auto getObstacle () -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
 
auto getRouteLanelets (double horizon=100) -> lanelet::Ids override
 
auto getWaypoints () -> const traffic_simulator_msgs::msg::WaypointsArray override
 
void onUpdate (double current_time, double step_time) override
 
void requestAcquirePosition (const CanonicalizedLaneletPose &)
 
void requestAcquirePosition (const geometry_msgs::msg::Pose &map_pose) override
 
void requestAssignRoute (const std::vector< geometry_msgs::msg::Pose > &) override
 
void requestAssignRoute (const std::vector< CanonicalizedLaneletPose > &) override
 
auto requestFollowTrajectory (const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
 
void requestLaneChange (const lanelet::Id to_lanelet_id) override
 
void requestLaneChange (const traffic_simulator::lane_change::Parameter &) override
 
void setVelocityLimit (double linear_velocity) override
 
void setAccelerationLimit (double acceleration) override
 
void setAccelerationRateLimit (double acceleration_rate) override
 
void setDecelerationLimit (double deceleration) override
 
void setDecelerationRateLimit (double deceleration_rate) override
 
void setBehaviorParameter (const traffic_simulator_msgs::msg::BehaviorParameter &) override
 
void setTrafficLightManager (const std::shared_ptr< traffic_simulator::TrafficLightManager > &) override
 
auto fillLaneletPose (CanonicalizedEntityStatus &status) -> void 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 auto asFieldOperatorApplication () const -> concealer::FieldOperatorApplication &
 
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 void onPostUpdate (double current_time, double step_time)
 
void resetDynamicConstraints ()
 
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 double, const speed_change::Transition, const speed_change::Constraint, const bool)
 
virtual void requestSpeedChange (const speed_change::RelativeTargetSpeed &, const speed_change::Transition, const speed_change::Constraint, const bool)
 
virtual void requestSpeedChange (double, bool)
 
virtual void requestSpeedChange (const speed_change::RelativeTargetSpeed &, bool)
 
virtual void requestClearRoute ()
 
virtual auto isControlledBySimulator () const -> bool
 
virtual auto setControlledBySimulator (bool) -> 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 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
 

Public Attributes

const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
 
- Public Attributes inherited from traffic_simulator::entity::EntityBase
const std::string name
 
bool verbose
 

Additional Inherited Members

- 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

◆ VehicleEntity()

traffic_simulator::entity::VehicleEntity::VehicleEntity ( const std::string &  name,
const CanonicalizedEntityStatus entity_status,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr,
const traffic_simulator_msgs::msg::VehicleParameters &  parameters,
const std::string &  plugin_name = BuiltinBehavior::defaultBehavior() 
)
explicit

◆ ~VehicleEntity()

traffic_simulator::entity::VehicleEntity::~VehicleEntity ( )
overridedefault

Member Function Documentation

◆ appendDebugMarker()

void traffic_simulator::entity::VehicleEntity::appendDebugMarker ( visualization_msgs::msg::MarkerArray &  marker_array)
overridevirtual

◆ cancelRequest()

void traffic_simulator::entity::VehicleEntity::cancelRequest ( )
overridevirtual

◆ fillLaneletPose()

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

◆ getBehaviorParameter()

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

◆ getCurrentAction()

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

◆ getDefaultDynamicConstraints()

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

◆ getDefaultMatchingDistanceForLaneletPoseCalculation()

auto traffic_simulator::entity::VehicleEntity::getDefaultMatchingDistanceForLaneletPoseCalculation ( ) const -> double
overridevirtual

◆ getEntityType()

auto traffic_simulator::entity::VehicleEntity::getEntityType ( ) const -> const traffic_simulator_msgs::msg::EntityType &
overridevirtual

◆ getEntityTypename()

auto traffic_simulator::entity::VehicleEntity::getEntityTypename ( ) const -> const std::string &
overridevirtual

◆ getGoalPoses()

auto traffic_simulator::entity::VehicleEntity::getGoalPoses ( ) -> std::vector<CanonicalizedLaneletPose>
overridevirtual

◆ getMaxAcceleration()

auto traffic_simulator::entity::VehicleEntity::getMaxAcceleration ( ) const -> double
overridevirtual

◆ getMaxDeceleration()

auto traffic_simulator::entity::VehicleEntity::getMaxDeceleration ( ) const -> double
overridevirtual

◆ getObstacle()

auto traffic_simulator::entity::VehicleEntity::getObstacle ( ) -> std::optional<traffic_simulator_msgs::msg::Obstacle>
overridevirtual

◆ getRouteLanelets()

auto traffic_simulator::entity::VehicleEntity::getRouteLanelets ( double  horizon = 100) -> lanelet::Ids
overridevirtual

◆ getWaypoints()

auto traffic_simulator::entity::VehicleEntity::getWaypoints ( ) -> const traffic_simulator_msgs::msg::WaypointsArray
overridevirtual

◆ onUpdate()

void traffic_simulator::entity::VehicleEntity::onUpdate ( double  current_time,
double  step_time 
)
overridevirtual

◆ requestAcquirePosition() [1/2]

void traffic_simulator::entity::VehicleEntity::requestAcquirePosition ( const CanonicalizedLaneletPose lanelet_pose)
virtual

◆ requestAcquirePosition() [2/2]

void traffic_simulator::entity::VehicleEntity::requestAcquirePosition ( const geometry_msgs::msg::Pose &  map_pose)
overridevirtual

◆ requestAssignRoute() [1/2]

void traffic_simulator::entity::VehicleEntity::requestAssignRoute ( const std::vector< CanonicalizedLaneletPose > &  waypoints)
overridevirtual

◆ requestAssignRoute() [2/2]

void traffic_simulator::entity::VehicleEntity::requestAssignRoute ( const std::vector< geometry_msgs::msg::Pose > &  waypoints)
overridevirtual

◆ requestFollowTrajectory()

auto traffic_simulator::entity::VehicleEntity::requestFollowTrajectory ( const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &  parameter) -> void
overridevirtual
Todo:
such a protection most likely makes sense, but test scenario RoutingAction.FollowTrajectoryAction-star has waypoints outside lanelet2

Reimplemented from traffic_simulator::entity::EntityBase.

◆ requestLaneChange() [1/2]

void traffic_simulator::entity::VehicleEntity::requestLaneChange ( const lanelet::Id  to_lanelet_id)
overridevirtual

◆ requestLaneChange() [2/2]

void traffic_simulator::entity::VehicleEntity::requestLaneChange ( const traffic_simulator::lane_change::Parameter parameter)
overridevirtual

◆ setAccelerationLimit()

void traffic_simulator::entity::VehicleEntity::setAccelerationLimit ( double  acceleration)
overridevirtual

◆ setAccelerationRateLimit()

void traffic_simulator::entity::VehicleEntity::setAccelerationRateLimit ( double  acceleration_rate)
overridevirtual

◆ setBehaviorParameter()

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

◆ setDecelerationLimit()

void traffic_simulator::entity::VehicleEntity::setDecelerationLimit ( double  deceleration)
overridevirtual

◆ setDecelerationRateLimit()

void traffic_simulator::entity::VehicleEntity::setDecelerationRateLimit ( double  deceleration_rate)
overridevirtual

◆ setTrafficLightManager()

void traffic_simulator::entity::VehicleEntity::setTrafficLightManager ( const std::shared_ptr< traffic_simulator::TrafficLightManager > &  ptr)
overridevirtual

◆ setVelocityLimit()

void traffic_simulator::entity::VehicleEntity::setVelocityLimit ( double  linear_velocity)
overridevirtual

Member Data Documentation

◆ vehicle_parameters

const traffic_simulator_msgs::msg::VehicleParameters traffic_simulator::entity::VehicleEntity::vehicle_parameters

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