15 #ifndef TRAFFIC_SIMULATOR__ENTITY__VEHICLE_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__VEHICLE_ENTITY_HPP_
20 #include <pluginlib/class_loader.hpp>
21 #include <pugixml.hpp>
22 #include <rclcpp/rclcpp.hpp>
27 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
28 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
29 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
43 static const std::string name =
"behavior_tree_plugin/VehicleBehaviorTree";
64 const std::shared_ptr<hdmap_utils::HdMapUtils> &,
65 const traffic_simulator_msgs::msg::VehicleParameters &,
70 void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array)
override;
99 auto
onUpdate(const
double current_time, const
double step_time) ->
void override;
104 const geometry_msgs::msg::
Pose & map_pose, const
RouteOption &) override;
136 behavior_plugin_ptr_->setLateralCollisionThreshold(value);
142 pluginlib::ClassLoader<entity_behavior::BehaviorPluginBase> loader_;
144 const std::shared_ptr<entity_behavior::BehaviorPluginBase> behavior_plugin_ptr_;
147 traffic_simulator::RoutingGraphType::VEHICLE_WITH_ROAD_SHOULDER};
149 std::shared_ptr<math::geometry::CatmullRomSpline> spline_;
151 lanelet::Ids previous_route_lanelets_;
Definition: route_planner.hpp:26
Definition: traffic_lights_base.hpp:44
Definition: entity_base.hpp:53
const std::string name
Definition: entity_base.hpp:351
Definition: vehicle_entity.hpp:37
void setDecelerationLimit(double deceleration) override
Definition: vehicle_entity.cpp:326
auto getEntityTypename() const -> const std::string &override
Definition: vehicle_entity.cpp:95
void requestAssignRoute(const std::vector< geometry_msgs::msg::Pose > &, const RouteOption &) override
Definition: vehicle_entity.cpp:219
auto requestLaneChange(const lanelet::Id to_lanelet_id) -> void override
Definition: vehicle_entity.cpp:266
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: vehicle_entity.cpp:130
void setVelocityLimit(double linear_velocity) override
Definition: vehicle_entity.cpp:296
void setAccelerationLimit(double acceleration) override
Definition: vehicle_entity.cpp:306
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) override
Definition: vehicle_entity.cpp:346
void setLateralCollisionThreshold(const std::optional< double > &value)
Definition: vehicle_entity.hpp:134
auto getCurrentAction() const -> std::string override
Definition: vehicle_entity.cpp:61
auto getDefaultMatchingDistanceForLaneletPoseCalculation() const -> double override
Definition: vehicle_entity.cpp:73
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: vehicle_entity.cpp:236
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: vehicle_entity.cpp:66
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())
Definition: vehicle_entity.cpp:29
void appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) override
Definition: vehicle_entity.cpp:49
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override
Definition: vehicle_entity.cpp:90
auto getGoalPoses() -> std::vector< geometry_msgs::msg::Pose > override
Definition: vehicle_entity.cpp:101
~VehicleEntity() override=default
auto onUpdate(const double current_time, const double step_time) -> void override
Definition: vehicle_entity.cpp:145
void requestAcquirePosition(const CanonicalizedLaneletPose &, const RouteOption &) override
Definition: vehicle_entity.cpp:180
void setAccelerationRateLimit(double acceleration_rate) override
Definition: vehicle_entity.cpp:316
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
Definition: vehicle_entity.hpp:139
void setDecelerationRateLimit(double deceleration_rate) override
Definition: vehicle_entity.cpp:336
auto getMaxAcceleration() const -> double override
Definition: vehicle_entity.cpp:282
auto getMaxDeceleration() const -> double override
Definition: vehicle_entity.cpp:289
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: vehicle_entity.cpp:115
void cancelRequest() override
Definition: vehicle_entity.cpp:55
void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &) override
Definition: vehicle_entity.cpp:352
auto getParameters() const -> const traffic_simulator_msgs::msg::VehicleParameters &
Definition: vehicle_entity.cpp:85
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: vehicle_entity.cpp:110
Definition: entity_status.hpp:31
Definition: lanelet_pose.hpp:35
Definition: lanelet_wrapper.hpp:43
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
traffic_simulator::lane_change::Parameter Parameter
Definition: lane_change.hpp:27
Definition: operators.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: vehicle_entity.hpp:40
static auto defaultBehavior() -> const std::string &
Definition: vehicle_entity.hpp:59
static auto doNothing() noexcept -> const std::string &
Definition: vehicle_entity.hpp:53
static auto behaviorTree() -> const std::string &
Definition: vehicle_entity.hpp:41
static auto contextGamma() -> const std::string &
Definition: vehicle_entity.hpp:47
Definition: route_option.hpp:25