scenario_simulator_v2 C++ API
Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
entity_behavior::VehicleActionNode Class Referenceabstract

#include <vehicle_action_node.hpp>

Inheritance diagram for entity_behavior::VehicleActionNode:
Inheritance graph
[legend]
Collaboration diagram for entity_behavior::VehicleActionNode:
Collaboration graph
[legend]

Public Member Functions

 VehicleActionNode (const std::string &name, const BT::NodeConfiguration &config)
 
 ~VehicleActionNode () override=default
 
void getBlackBoardValues ()
 
auto calculateUpdatedEntityStatus (double target_speed) const -> traffic_simulator::EntityStatus
 
auto calculateUpdatedEntityStatusInWorldFrame (double target_speed) const -> traffic_simulator::EntityStatus
 
virtual const traffic_simulator_msgs::msg::WaypointsArray calculateWaypoints ()=0
 
virtual const std::optional< traffic_simulator_msgs::msg::Obstacle > calculateObstacle (const traffic_simulator_msgs::msg::WaypointsArray &waypoints)=0
 
- Public Member Functions inherited from entity_behavior::ActionNode
 ActionNode (const std::string &name, const BT::NodeConfiguration &config)
 
 ~ActionNode () override=default
 
auto foundConflictingEntity (const lanelet::Ids &following_lanelets) const -> bool
 
auto getDistanceToConflictingEntity (const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
 
auto getFrontEntityName (const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
 
auto calculateStopDistance (const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
 
auto getDistanceToFrontEntity (const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
 
auto getDistanceToStopLine (const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
 
auto getDistanceToTrafficLightStopLine (const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
 
auto getRightOfWayEntities () const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
 
auto getRightOfWayEntities (const lanelet::Ids &following_lanelets) const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
 
auto getYieldStopDistance (const lanelet::Ids &following_lanelets) const -> std::optional< double >
 
auto getOtherEntityStatus (lanelet::Id lanelet_id) const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
 
auto stopEntity () const -> void
 
auto getHorizon () const -> double
 
auto executeTick () -> BT::NodeStatus override
 throws if the derived class return RUNNING. More...
 
void halt () override final
 
auto getBlackBoardValues () -> void
 
auto getEntityStatus (const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus &
 
auto getDistanceToTargetEntityPolygon (const math::geometry::CatmullRomSplineInterface &spline, const std::string target_name, double width_extension_right=0.0, double width_extension_left=0.0, double length_extension_front=0.0, double length_extension_rear=0.0) const -> std::optional< double >
 
auto setCanonicalizedEntityStatus (const traffic_simulator::EntityStatus &entity_status) -> void
 
auto calculateUpdatedEntityStatus (double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
 
auto calculateUpdatedEntityStatusInWorldFrame (double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
- Static Public Member Functions inherited from entity_behavior::ActionNode
static BT::PortsList providedPorts ()
 

Protected Attributes

traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter
 
traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
 
std::shared_ptr< math::geometry::CatmullRomSplinereference_trajectory
 
std::unique_ptr< math::geometry::CatmullRomSubsplinetrajectory
 
- Protected Attributes inherited from entity_behavior::ActionNode
traffic_simulator::behavior::Request request
 
std::shared_ptr< hdmap_utils::HdMapUtilshdmap_utils
 
std::shared_ptr< traffic_simulator::TrafficLightManagertraffic_light_manager
 
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatuscanonicalized_entity_status
 
double current_time
 
double step_time
 
double default_matching_distance_for_lanelet_pose_calculation
 
std::optional< double > target_speed
 
EntityStatusDict other_entity_status
 
lanelet::Ids route_lanelets
 

Constructor & Destructor Documentation

◆ VehicleActionNode()

entity_behavior::VehicleActionNode::VehicleActionNode ( const std::string &  name,
const BT::NodeConfiguration &  config 
)

◆ ~VehicleActionNode()

entity_behavior::VehicleActionNode::~VehicleActionNode ( )
overridedefault

Member Function Documentation

◆ calculateObstacle()

virtual const std::optional<traffic_simulator_msgs::msg::Obstacle> entity_behavior::VehicleActionNode::calculateObstacle ( const traffic_simulator_msgs::msg::WaypointsArray &  waypoints)
pure virtual

◆ calculateUpdatedEntityStatus()

auto entity_behavior::VehicleActionNode::calculateUpdatedEntityStatus ( double  target_speed) const -> traffic_simulator::EntityStatus

◆ calculateUpdatedEntityStatusInWorldFrame()

auto entity_behavior::VehicleActionNode::calculateUpdatedEntityStatusInWorldFrame ( double  target_speed) const -> traffic_simulator::EntityStatus

◆ calculateWaypoints()

virtual const traffic_simulator_msgs::msg::WaypointsArray entity_behavior::VehicleActionNode::calculateWaypoints ( )
pure virtual

◆ getBlackBoardValues()

void entity_behavior::VehicleActionNode::getBlackBoardValues ( )

◆ providedPorts()

static BT::PortsList entity_behavior::VehicleActionNode::providedPorts ( )
inlinestatic

Member Data Documentation

◆ behavior_parameter

traffic_simulator_msgs::msg::BehaviorParameter entity_behavior::VehicleActionNode::behavior_parameter
protected

◆ reference_trajectory

std::shared_ptr<math::geometry::CatmullRomSpline> entity_behavior::VehicleActionNode::reference_trajectory
protected

◆ trajectory

std::unique_ptr<math::geometry::CatmullRomSubspline> entity_behavior::VehicleActionNode::trajectory
protected

◆ vehicle_parameters

traffic_simulator_msgs::msg::VehicleParameters entity_behavior::VehicleActionNode::vehicle_parameters
protected

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