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

#include <ego_entity.hpp>

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

Public Member Functions

 EgoEntity ()=delete
 
 EgoEntity (const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &, const traffic_simulator_msgs::msg::VehicleParameters &, const Configuration &, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &)
 
 EgoEntity (EgoEntity &&)=delete
 
 EgoEntity (const EgoEntity &)=delete
 
 ~EgoEntity () override=default
 
auto operator= (EgoEntity &&) -> EgoEntity &=delete
 
auto operator= (const EgoEntity &) -> EgoEntity &=delete
 
auto getCurrentAction () const -> std::string override
 
auto getCurrentPose () const -> const geometry_msgs::msg::Pose &
 
auto getDefaultDynamicConstraints () const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
 
auto getBehaviorParameter () const -> traffic_simulator_msgs::msg::BehaviorParameter override
 
auto getEntityStatus (const double, const double) const -> const CanonicalizedEntityStatus
 
auto getEntityTypename () const -> const std::string &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
 
auto updateFieldOperatorApplication () -> void
 
void onUpdate (double current_time, double step_time) override
 
void requestAcquirePosition (const CanonicalizedLaneletPose &) override
 
void requestAcquirePosition (const geometry_msgs::msg::Pose &map_pose) override
 
void requestAssignRoute (const std::vector< CanonicalizedLaneletPose > &) override
 
void requestAssignRoute (const std::vector< geometry_msgs::msg::Pose > &) override
 
auto requestFollowTrajectory (const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
 
auto requestLaneChange (const lanelet::Id) -> void override
 
auto requestLaneChange (const lane_change::Parameter &) -> void override
 
auto requestSpeedChange (const double, const speed_change::Transition, const speed_change::Constraint, const bool continuous) -> void override
 
auto requestSpeedChange (const speed_change::RelativeTargetSpeed &, const speed_change::Transition, const speed_change::Constraint, const bool continuous) -> void override
 
auto requestClearRoute () -> void
 
auto requestReplanRoute (const std::vector< geometry_msgs::msg::PoseStamped > &route) -> void
 
auto requestAutoModeForCooperation (const std::string &module_name, bool enable) -> void
 
auto isControlledBySimulator () const -> bool override
 
auto setControlledBySimulator (bool state) -> void override
 
auto setBehaviorParameter (const traffic_simulator_msgs::msg::BehaviorParameter &) -> void override
 
void requestSpeedChange (double, bool continuous) override
 
void requestSpeedChange (const speed_change::RelativeTargetSpeed &target_speed, bool continuous) override
 
auto setVelocityLimit (double) -> void override
 
auto setMapPose (const geometry_msgs::msg::Pose &map_pose) -> void override
 
template<typename ParameterType >
auto setParameter (const std::string &name, const ParameterType &default_value={}) -> ParameterType
 
template<typename... Ts>
auto setStatus (Ts &&... xs) -> void
 
auto engage () -> void
 
auto isEngaged () const -> bool
 
auto isEngageable () const -> bool
 
auto sendCooperateCommand (const std::string &module_name, const std::string &command) -> void
 
auto getMinimumRiskManeuverBehaviorName () const -> std::string
 
auto getMinimumRiskManeuverStateName () const -> std::string
 
auto getEmergencyStateName () const -> std::string
 
auto getTurnIndicatorsCommandName () const -> std::string
 
- Public Member Functions inherited from traffic_simulator::entity::VehicleEntity
 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 getEntityTypename () const -> const std::string &override
 
auto getGoalPoses () -> std::vector< CanonicalizedLaneletPose > override
 
auto getParameters () const -> const traffic_simulator_msgs::msg::VehicleParameters &
 
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
 
auto onUpdate (const double current_time, const double step_time) -> void 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
 
auto requestLaneChange (const lanelet::Id to_lanelet_id) -> void override
 
auto requestLaneChange (const traffic_simulator::lane_change::Parameter &) -> void 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 setTrafficLights (const std::shared_ptr< traffic_simulator::TrafficLightsBase > &) override
 
- Public Member Functions inherited from traffic_simulator::entity::EntityBase
 EntityBase (const std::string &name, const CanonicalizedEntityStatus &entity_status, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr)
 
 EntityBase (const EntityBase &)=delete
 
EntityBaseoperator= (const EntityBase &)=delete
 
 EntityBase (EntityBase &&) noexcept=delete
 
EntityBaseoperator= (EntityBase &&) noexcept=delete
 
virtual ~EntityBase ()=default
 
template<typename EntityType >
auto is () const -> bool
 
template<typename EntityType >
auto as () -> EntityType &
 
template<typename EntityType >
auto as () const -> const EntityType &
 
auto getBoundingBox () const noexcept -> const traffic_simulator_msgs::msg::BoundingBox &
 Get BoundingBox of the entity. More...
 
auto getCanonicalizedStatus () const noexcept -> const CanonicalizedEntityStatus &
 Get CanonicalizedStatus of the entity. More...
 
auto getCanonicalizedStatusBeforeUpdate () const noexcept -> const CanonicalizedEntityStatus &
 Get CanonicalizedStatusBeforeUpdate of the entity. More...
 
auto getCurrentAccel () const noexcept -> const geometry_msgs::msg::Accel &
 Get CurrentAccel of the entity. More...
 
auto getCurrentTwist () const noexcept -> const 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 getEntitySubtype () const noexcept -> const traffic_simulator_msgs::msg::EntitySubtype &
 Get EntitySubtype of the entity. More...
 
auto getEntityType () const noexcept -> const traffic_simulator_msgs::msg::EntityType &
 Get EntityType of the entity. More...
 
auto getLinearJerk () const noexcept -> double
 Get LinearJerk of the entity. More...
 
auto getMapPose () const noexcept -> const geometry_msgs::msg::Pose &
 Get MapPose of the entity. More...
 
auto getStandStillDuration () const noexcept -> double
 Get StandStillDuration of the entity. More...
 
auto getTraveledDistance () const noexcept -> double
 Get TraveledDistance of the entity. More...
 
auto getName () const noexcept -> const std::string &
 Get Name of the entity. More...
 
auto get2DPolygon () const -> std::vector< geometry_msgs::msg::Point >
 
auto isStopped () const -> bool
 
auto isNearbyPosition (const geometry_msgs::msg::Pose &pose, const double tolerance) const -> bool
 
auto isNearbyPosition (const CanonicalizedLaneletPose &lanelet_pose, const double tolerance) const -> bool
 
auto isInLanelet () const -> bool
 
auto isInLanelet (const lanelet::Id lanelet_id, std::optional< double > tolerance=std::nullopt) const -> bool
 
auto getCanonicalizedLaneletPose () const -> std::optional< CanonicalizedLaneletPose >
 
auto getCanonicalizedLaneletPose (const double matching_distance) const -> std::optional< CanonicalizedLaneletPose >
 
virtual auto onPostUpdate (const double current_time, const double step_time) -> void
 
void resetDynamicConstraints ()
 
auto requestLaneChange (const lane_change::Direction &direction) -> void
 
auto requestLaneChange (const lane_change::AbsoluteTarget &target, const lane_change::TrajectoryShape trajectory_shape, const lane_change::Constraint &constraint) -> void
 
auto requestLaneChange (const lane_change::RelativeTarget &target, const lane_change::TrajectoryShape trajectory_shape, const lane_change::Constraint &constraint) -> void
 
virtual void requestWalkStraight ()
 
void setDynamicConstraints (const traffic_simulator_msgs::msg::DynamicConstraints &constraints)
 
void setOtherStatus (const std::unordered_map< std::string, CanonicalizedEntityStatus > &status)
 
auto setCanonicalizedStatus (const CanonicalizedEntityStatus &status) -> void
 
virtual auto setStatus (const EntityStatus &status) -> void
 
virtual auto setStatus (const EntityStatus &status, const lanelet::Ids &lanelet_ids) -> void
 
virtual auto setStatus (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
virtual auto setStatus (const geometry_msgs::msg::Pose &reference_pose, const geometry_msgs::msg::Pose &relative_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
virtual auto setStatus (const geometry_msgs::msg::Pose &reference_pose, const geometry_msgs::msg::Point &relative_position, const geometry_msgs::msg::Vector3 &relative_rpy, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
virtual auto setStatus (const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
virtual auto setStatus (const LaneletPose &lanelet_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
virtual auto setLinearAcceleration (const double linear_acceleration) -> void
 
virtual auto setLinearVelocity (const double linear_velocity) -> void
 
virtual auto activateOutOfRangeJob (const double min_velocity, const double max_velocity, const double min_acceleration, const double max_acceleration, const double min_jerk, const double max_jerk) -> void
 
auto setTwist (const geometry_msgs::msg::Twist &twist) -> void
 
auto setAcceleration (const geometry_msgs::msg::Accel &accel) -> void
 
auto setAction (const std::string &action) -> void
 
auto setLinearJerk (const double liner_jerk) -> void
 
void stopAtCurrentPosition ()
 
void updateEntityStatusTimestamp (const double current_time)
 
auto requestSynchronize (const std::string &target_name, const CanonicalizedLaneletPose &target_sync_pose, const CanonicalizedLaneletPose &entity_target, const double target_speed, const double tolerance) -> bool
 

Additional Inherited Members

- Public Attributes inherited from traffic_simulator::entity::VehicleEntity
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
 
- Public Attributes inherited from traffic_simulator::entity::EntityBase
const std::string name
 
bool verbose
 
- Protected Attributes inherited from traffic_simulator::entity::EntityBase
std::shared_ptr< CanonicalizedEntityStatusstatus_
 
CanonicalizedEntityStatus status_before_update_
 
std::shared_ptr< hdmap_utils::HdMapUtilshdmap_utils_ptr_
 
std::shared_ptr< traffic_simulator::TrafficLightsBasetraffic_lights_
 
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

◆ EgoEntity() [1/4]

traffic_simulator::entity::EgoEntity::EgoEntity ( )
explicitdelete

◆ EgoEntity() [2/4]

traffic_simulator::entity::EgoEntity::EgoEntity ( 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 Configuration configuration,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  node_parameters 
)
explicit

◆ EgoEntity() [3/4]

traffic_simulator::entity::EgoEntity::EgoEntity ( EgoEntity &&  )
explicitdelete

◆ EgoEntity() [4/4]

traffic_simulator::entity::EgoEntity::EgoEntity ( const EgoEntity )
explicitdelete

◆ ~EgoEntity()

traffic_simulator::entity::EgoEntity::~EgoEntity ( )
overridedefault

Member Function Documentation

◆ engage()

auto traffic_simulator::entity::EgoEntity::engage ( ) -> void

◆ getBehaviorParameter()

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

TODO, Input values get from autoware.

Implements traffic_simulator::entity::EntityBase.

◆ getCurrentAction()

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

◆ getCurrentPose()

auto traffic_simulator::entity::EgoEntity::getCurrentPose ( ) const -> const geometry_msgs::msg::Pose &

◆ getDefaultDynamicConstraints()

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

◆ getEmergencyStateName()

auto traffic_simulator::entity::EgoEntity::getEmergencyStateName ( ) const -> std::string

◆ getEntityStatus()

auto traffic_simulator::entity::EgoEntity::getEntityStatus ( const double  ,
const double   
) const -> const CanonicalizedEntityStatus

◆ getEntityTypename()

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

◆ getMinimumRiskManeuverBehaviorName()

auto traffic_simulator::entity::EgoEntity::getMinimumRiskManeuverBehaviorName ( ) const -> std::string

◆ getMinimumRiskManeuverStateName()

auto traffic_simulator::entity::EgoEntity::getMinimumRiskManeuverStateName ( ) const -> std::string

◆ getObstacle()

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

◆ getRouteLanelets()

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

◆ getTurnIndicatorsCommandName()

auto traffic_simulator::entity::EgoEntity::getTurnIndicatorsCommandName ( ) const -> std::string

◆ getWaypoints()

auto traffic_simulator::entity::EgoEntity::getWaypoints ( ) -> const traffic_simulator_msgs::msg::WaypointsArray
overridevirtual
Note
return empty array because this function is used for visualization Autoware's trajectory is already visualized in RViz there is no need to visualize it second time

Implements traffic_simulator::entity::EntityBase.

◆ isControlledBySimulator()

auto traffic_simulator::entity::EgoEntity::isControlledBySimulator ( ) const -> bool
overridevirtual

◆ isEngageable()

auto traffic_simulator::entity::EgoEntity::isEngageable ( ) const -> bool

◆ isEngaged()

auto traffic_simulator::entity::EgoEntity::isEngaged ( ) const -> bool

◆ onUpdate()

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

◆ operator=() [1/2]

auto traffic_simulator::entity::EgoEntity::operator= ( const EgoEntity ) -> EgoEntity &=delete
delete

◆ operator=() [2/2]

auto traffic_simulator::entity::EgoEntity::operator= ( EgoEntity &&  ) -> EgoEntity &=delete
delete

◆ requestAcquirePosition() [1/2]

void traffic_simulator::entity::EgoEntity::requestAcquirePosition ( const CanonicalizedLaneletPose lanelet_pose)
overridevirtual

◆ requestAcquirePosition() [2/2]

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

◆ requestAssignRoute() [1/2]

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

◆ requestAssignRoute() [2/2]

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

◆ requestAutoModeForCooperation()

auto traffic_simulator::entity::EgoEntity::requestAutoModeForCooperation ( const std::string &  module_name,
bool  enable 
) -> void

◆ requestClearRoute()

auto traffic_simulator::entity::EgoEntity::requestClearRoute ( ) -> void

◆ requestFollowTrajectory()

auto traffic_simulator::entity::EgoEntity::requestFollowTrajectory ( const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &  parameter) -> void
overridevirtual

◆ requestLaneChange() [1/2]

auto traffic_simulator::entity::EgoEntity::requestLaneChange ( const lane_change::Parameter ) -> void
overridevirtual

◆ requestLaneChange() [2/2]

auto traffic_simulator::entity::EgoEntity::requestLaneChange ( const lanelet::Id  ) -> void
overridevirtual

◆ requestReplanRoute()

auto traffic_simulator::entity::EgoEntity::requestReplanRoute ( const std::vector< geometry_msgs::msg::PoseStamped > &  route) -> void

◆ requestSpeedChange() [1/4]

auto traffic_simulator::entity::EgoEntity::requestSpeedChange ( const double  target_speed,
const speed_change::Transition  ,
const speed_change::Constraint  ,
const bool  continuous 
) -> void
overridevirtual

◆ requestSpeedChange() [2/4]

auto traffic_simulator::entity::EgoEntity::requestSpeedChange ( const speed_change::RelativeTargetSpeed ,
const speed_change::Transition  ,
const speed_change::Constraint  ,
const bool  continuous 
) -> void
overridevirtual

◆ requestSpeedChange() [3/4]

auto traffic_simulator::entity::EgoEntity::requestSpeedChange ( const speed_change::RelativeTargetSpeed target_speed,
bool  continuous 
)
overridevirtual

◆ requestSpeedChange() [4/4]

auto traffic_simulator::entity::EgoEntity::requestSpeedChange ( double  value,
bool  continuous 
)
overridevirtual

◆ sendCooperateCommand()

auto traffic_simulator::entity::EgoEntity::sendCooperateCommand ( const std::string &  module_name,
const std::string &  command 
) -> void

◆ setBehaviorParameter()

auto traffic_simulator::entity::EgoEntity::setBehaviorParameter ( const traffic_simulator_msgs::msg::BehaviorParameter &  behavior_parameter) -> void
overridevirtual

◆ setControlledBySimulator()

auto traffic_simulator::entity::EgoEntity::setControlledBySimulator ( bool  state) -> void
inlineoverridevirtual

◆ setMapPose()

auto traffic_simulator::entity::EgoEntity::setMapPose ( const geometry_msgs::msg::Pose &  map_pose) -> void
overridevirtual

◆ setParameter()

template<typename ParameterType >
auto traffic_simulator::entity::EgoEntity::setParameter ( const std::string &  name,
const ParameterType &  default_value = {} 
) -> ParameterType
inline

◆ setStatus()

template<typename... Ts>
auto traffic_simulator::entity::EgoEntity::setStatus ( Ts &&...  xs) -> void
inline

◆ setVelocityLimit()

auto traffic_simulator::entity::EgoEntity::setVelocityLimit ( double  value) -> void
overridevirtual

◆ updateFieldOperatorApplication()

auto traffic_simulator::entity::EgoEntity::updateFieldOperatorApplication ( ) -> void

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