| scenario_simulator_v2 C++ API
    | 
#include <vehicle_action_node.hpp>


| Public Member Functions | |
| VehicleActionNode (const std::string &name, const BT::NodeConfiguration &config) | |
| ~VehicleActionNode () override=default | |
| void | getBlackBoardValues () override | 
| 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 | 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 | getFrontEntityNameAndDistanceByTrajectory (const std::vector< geometry_msgs::msg::Point > &waypoints, const double width, const std::size_t num_segments) const -> std::optional< std::pair< std::string, 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 | 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 | getEntityStatus (const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus & | 
| auto | setCanonicalizedEntityStatus (const traffic_simulator::EntityStatus &entity_status) -> void | 
| auto | calculateUpdatedEntityStatus (const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus | 
| auto | calculateUpdatedEntityStatusInWorldFrame (const double local_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::VehicleParameters | vehicle_parameters | 
| std::shared_ptr< math::geometry::CatmullRomSpline > | reference_trajectory | 
| std::unique_ptr< math::geometry::CatmullRomSubspline > | trajectory | 
|  Protected Attributes inherited from entity_behavior::ActionNode | |
| traffic_simulator::behavior::Request | request_ | 
| std::shared_ptr< hdmap_utils::HdMapUtils > | hdmap_utils_ | 
| std::shared_ptr< traffic_simulator::TrafficLightsBase > | traffic_lights_ | 
| std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > | canonicalized_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_ | 
| traffic_simulator_msgs::msg::BehaviorParameter | behavior_parameter_ | 
| std::optional< double > | lateral_collision_threshold_ | 
| Additional Inherited Members | |
|  Protected Member Functions inherited from entity_behavior::ActionNode | |
| virtual bool | checkPreconditions () | 
| virtual BT::NodeStatus | doAction ()=0 | 
| auto | getDistanceToTargetEntity (const math::geometry::CatmullRomSplineInterface &spline, const traffic_simulator::CanonicalizedEntityStatus &status) const -> std::optional< double > | 
| entity_behavior::VehicleActionNode::VehicleActionNode | ( | const std::string & | name, | 
| const BT::NodeConfiguration & | config | ||
| ) | 
| 
 | overridedefault | 
| 
 | pure virtual | 
Implemented in entity_behavior::vehicle::LaneChangeAction, entity_behavior::vehicle::follow_lane_sequence::YieldAction, entity_behavior::vehicle::follow_lane_sequence::StopAtTrafficLightAction, entity_behavior::vehicle::follow_lane_sequence::StopAtStopLineAction, entity_behavior::vehicle::follow_lane_sequence::StopAtCrossingEntityAction, entity_behavior::vehicle::follow_lane_sequence::MoveBackwardAction, entity_behavior::vehicle::follow_lane_sequence::FollowLaneAction, entity_behavior::vehicle::follow_lane_sequence::FollowFrontEntityAction, and entity_behavior::vehicle::FollowPolylineTrajectoryAction.
| auto entity_behavior::VehicleActionNode::calculateUpdatedEntityStatus | ( | double | target_speed | ) | const -> traffic_simulator::EntityStatus | 
| auto entity_behavior::VehicleActionNode::calculateUpdatedEntityStatusInWorldFrame | ( | double | target_speed | ) | const -> traffic_simulator::EntityStatus | 
| 
 | pure virtual | 
Implemented in entity_behavior::vehicle::LaneChangeAction, entity_behavior::vehicle::follow_lane_sequence::YieldAction, entity_behavior::vehicle::follow_lane_sequence::StopAtTrafficLightAction, entity_behavior::vehicle::follow_lane_sequence::StopAtStopLineAction, entity_behavior::vehicle::follow_lane_sequence::StopAtCrossingEntityAction, entity_behavior::vehicle::follow_lane_sequence::MoveBackwardAction, entity_behavior::vehicle::follow_lane_sequence::FollowLaneAction, entity_behavior::vehicle::follow_lane_sequence::FollowFrontEntityAction, and entity_behavior::vehicle::FollowPolylineTrajectoryAction.
| 
 | overridevirtual | 
Reimplemented from entity_behavior::ActionNode.
| 
 | inlinestatic | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected |