diff --git a/autoware_launch/config/planning/neural_net_planner/diffusion_planner.param.yaml b/autoware_launch/config/planning/neural_net_planner/diffusion_planner.param.yaml
new file mode 100644
index 0000000000..38c13c15a7
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/diffusion_planner.param.yaml
@@ -0,0 +1,29 @@
+/**:
+ ros__parameters:
+ plugins_path: $(find-pkg-share autoware_tensorrt_plugins)/plugins/libautoware_tensorrt_plugins.so
+ onnx_model_path: $(env HOME)/autoware_data/diffusion_planner/v4.0/diffusion_planner.onnx
+ args_path: $(env HOME)/autoware_data/diffusion_planner/v4.0/diffusion_planner.param.json
+ planning_frequency_hz: 10.0
+ ignore_neighbors: false
+ ignore_unknown_neighbors: true
+ traffic_light_group_msg_timeout_seconds: 0.2
+ batch_size: 1
+ temperature: [0.0]
+ velocity_smoothing_window: 8
+ stopping_threshold: 0.3
+ turn_indicator_keep_offset: -1.25
+ turn_indicator_hold_duration: 1.0
+ shift_x: false
+ delay_step: 0
+ line_string_max_step_m: 5.0
+ use_time_interpolation: false
+ planning_factor:
+ enable_stop: true
+ enable_slowdown: false
+ stop_keep_duration_threshold: 1.0 # [s]
+ stop_velocity_threshold: 0.1 # [m/s]
+ slowdown_accel_threshold: -0.3 # [m/s^2]
+ debug_params:
+ publish_debug_route: true
+ publish_debug_map: false
+ publish_debug_linestrings: true
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_modifier.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_modifier.param.yaml
new file mode 100644
index 0000000000..1041990ded
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_modifier.param.yaml
@@ -0,0 +1,69 @@
+/**:
+ ros__parameters:
+ plugin_names:
+ - "autoware::trajectory_modifier::plugin::ObstacleStop"
+ - "autoware::trajectory_modifier::plugin::StopPointFixer"
+ use_stop_point_fixer: true
+ use_obstacle_stop: true
+ trajectory_time_step: 0.1 # [s]
+
+ # Stop Point Fixer Plugin Parameters
+ stop_point_fixer:
+ force_stop_long_stopped_trajectories: true # Force zero velocity trajectory for trajectories with long stops
+ force_stop_close_stopped_trajectories: true # Force zero velocity trajectory for trajectories with stops close to ego
+ velocity_threshold: 0.25 # [m/s]
+ min_distance_threshold: 1.0 # [m]
+ min_stop_duration: 0.5 # [s]
+
+ # Obstacle Stop Plugin Parameters
+ obstacle_stop:
+ use_objects: true
+ use_pointcloud: true
+ enable_stop_for_objects: true
+ enable_stop_for_pointcloud: false
+ stop_margin: 6.0 # [m]
+ nominal_stopping_decel: 1.0 # [m/s^2]
+ maximum_stopping_decel: 4.0 # [m/s^2]
+ stopping_jerk: 3.0 # [m/s^3]
+ lateral_margin: 0.0 # lateral margin on top of ego width from trajectory to consider for obstacle stop [m]
+ arrived_distance_threshold: 0.5 # threshold to check if the ego vehicle has arrived at the stop point [m]
+
+ obstacle_tracking:
+ on_time_buffer: 0.5
+ off_time_buffer: 1.0
+ object_distance_th: 1.0 # [m]
+ object_yaw_th: 0.1745 # [rad] (10 degrees)
+ pcd_distance_th: 0.5 # [m]
+ grace_period: 0.2 # [s]
+
+ objects:
+ object_types: ["car", "truck", "bus", "trailer", "motorcycle", "bicycle", "pedestrian"] # object types to consider for obstacle stop
+ max_velocity_th: 1.0 # maximum velocity threshold for target object [m/s]
+
+ pointcloud:
+ height_buffer: 0.5 # height buffer to add above ego height [m]
+ min_height: 0.2 # minimum height of pointcloud [m]
+ voxel_grid_filter:
+ x: 0.2
+ y: 0.2
+ z: 0.2
+ min_size: 3
+ clustering:
+ tolerance: 0.5 #[m]
+ min_height: 0.5
+ min_size: 10
+ max_size: 10000
+
+ rss_params:
+ enable: true
+ object_decel:
+ car: 1.5
+ truck: 1.5
+ bus: 1.5
+ trailer: 1.5
+ motorcycle: 3.0
+ bicycle: 5.0
+ pedestrian: 5.0
+ reaction_time: 0.2 # [s]
+ safety_margin: 2.0 # [m]
+ min_vel_th: 0.5 # [m/s] minimum object velocity to consider for rss check
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer.param.yaml
new file mode 100644
index 0000000000..af6eb05faf
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer.param.yaml
@@ -0,0 +1,23 @@
+/**:
+ ros__parameters:
+ # Plugin execution order - plugins will run in this order
+ plugin_names:
+ - "autoware::trajectory_optimizer::plugin::TrajectoryPointFixer"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryKinematicFeasibilityEnforcer"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryQPSmoother"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryKinematicFeasibilityEnforcer"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryVelocityOptimizer"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryEBSmootherOptimizer"
+ - "autoware::trajectory_optimizer::plugin::TrajectorySplineSmoother"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryMPTOptimizer"
+ - "autoware::trajectory_optimizer::plugin::TrajectoryExtender"
+
+ # Plugin activation flags - control runtime enable/disable
+ use_akima_spline_interpolation: true
+ use_eb_smoother: false
+ use_qp_smoother: true
+ use_trajectory_point_fixer: true
+ use_velocity_optimizer: true
+ use_trajectory_extender: false
+ use_kinematic_feasibility_enforcer: true
+ use_mpt_optimizer: false
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_extender.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_extender.param.yaml
new file mode 100644
index 0000000000..08b1406750
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_extender.param.yaml
@@ -0,0 +1,9 @@
+/**:
+ ros__parameters:
+ trajectory_extender:
+ # Trajectory matching thresholds
+ nearest_dist_threshold_m: 1.5 # [m] Distance threshold for trajectory matching
+ nearest_yaw_threshold_deg: 60.0 # [deg] Yaw threshold for trajectory matching
+
+ # Backward extension
+ backward_trajectory_extension_m: 5.0 # [m] Length to extend trajectory backward using ego history
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_kinematic_feasibility_enforcer.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_kinematic_feasibility_enforcer.param.yaml
new file mode 100644
index 0000000000..4230d077a2
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_kinematic_feasibility_enforcer.param.yaml
@@ -0,0 +1,8 @@
+/**:
+ ros__parameters:
+ # Plugin-specific parameters
+ trajectory_kinematic_feasibility:
+ # Maximum yaw rate [rad/s]. See kinematic_feasibility_enforcer.md for details
+ max_yaw_rate_rad_s: 0.7
+ # Time discretization
+ time_step_s: 0.1 # Fixed time step for yaw rate calculations [s]
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_mpt_optimizer.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_mpt_optimizer.param.yaml
new file mode 100644
index 0000000000..ed01c57349
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_mpt_optimizer.param.yaml
@@ -0,0 +1,91 @@
+/**:
+ ros__parameters:
+ trajectory_mpt_optimizer:
+ # Bounds Generation (custom parameters for trajectory_optimizer)
+ corridor_width_m: 3.5
+ enable_adaptive_width: true
+ curvature_width_factor: 0.5
+ velocity_width_factor: 0.3
+ min_clearance_m: 0.5
+ reset_previous_data_each_iteration: true
+ enable_debug_info: false
+ output_delta_arc_length_m: 1.0
+ output_backward_traj_length_m: 5.0
+ ego_nearest_dist_threshold_m: 3.0
+ ego_nearest_yaw_threshold_deg: 45.0
+ acceleration_moving_average_window: 5 # Moving average window size (larger = smoother)
+
+ # MPT Algorithm Parameters (required by autoware_path_optimizer MPTOptimizer)
+ # NOTE: These are solver parameters passed to the underlying MPT optimizer.
+ # Clearance parameters use "road" terminology from the solver, but in this implementation
+ # they represent clearance from the generated corridor bounds (simple perpendicular offsets),
+ # NOT actual road boundaries or drivable area from maps.
+ mpt:
+ option:
+ steer_limit_constraint: false
+ visualize_sampling_num: 1
+ enable_manual_warm_start: false
+ enable_warm_start: false
+ enable_optimization_validation: false
+
+ common:
+ num_points: 100
+ delta_arc_length: 1.0
+
+ clearance:
+ hard_clearance_from_road: 0.0 # Clearance from corridor bounds (not actual road)
+ soft_clearance_from_road: 0.1 # Clearance from corridor bounds (not actual road)
+
+ weight:
+ soft_collision_free_weight: 1.0
+ lat_error_weight: 1.0
+ yaw_error_weight: 0.0
+ yaw_error_rate_weight: 0.0
+ steer_input_weight: 1.0
+ steer_rate_weight: 1.0
+ terminal_lat_error_weight: 100.0
+ terminal_yaw_error_weight: 100.0
+ goal_lat_error_weight: 1000.0
+ goal_yaw_error_weight: 1000.0
+
+ avoidance:
+ max_bound_fixing_time: 1.0
+ max_longitudinal_margin_for_bound_violation: 1.0
+ max_avoidance_cost: 0.5
+ avoidance_cost_margin: 0.0
+ avoidance_cost_band_length: 5.0
+ avoidance_cost_decrease_rate: 0.05
+ min_drivable_width: 0.2
+
+ weight:
+ lat_error_weight: 0.0
+ yaw_error_weight: 10.0
+ steer_input_weight: 100.0
+
+ collision_free_constraints:
+ # NOTE: Collision avoidance is NOT active in this implementation.
+ # These parameters are part of the MPT solver configuration but unused
+ # because we don't provide obstacle data - only geometric corridor bounds.
+ option:
+ l_inf_norm: true
+ soft_constraint: true
+ hard_constraint: false
+
+ vehicle_circles:
+ method: "fitting_uniform_circle"
+
+ bicycle_model:
+ num_for_calculation: 3
+ front_radius_ratio: 1.0
+ rear_radius_ratio: 1.0
+
+ uniform_circle:
+ num: 3
+ radius_ratio: 1.0
+
+ fitting_uniform_circle:
+ num: 3
+
+ validation:
+ max_lat_error: 5.0
+ max_yaw_error: 1.046
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_point_fixer.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_point_fixer.param.yaml
new file mode 100644
index 0000000000..03816c154e
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_point_fixer.param.yaml
@@ -0,0 +1,9 @@
+/**:
+ ros__parameters:
+ trajectory_point_fixer:
+ # Distance thresholds for point processing
+ remove_close_points: true # Enable removal of close proximity points
+ resample_close_points: true # Enable resampling of close proximity points
+ min_dist_to_remove_m: 0.01 # [m] Minimum distance to remove close proximity points
+ min_dist_to_resample_m: 0.05 # [m] Minimum distance to merge close proximity points
+ stop_detection_velocity_threshold_mps: 0.3 # [m/s] Velocity threshold for fallback stop detection in slow clusters
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_qp_smoother.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_qp_smoother.param.yaml
new file mode 100644
index 0000000000..4744aa3df0
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_qp_smoother.param.yaml
@@ -0,0 +1,34 @@
+/**:
+ ros__parameters:
+ trajectory_qp_smoother:
+ # QP Smoother Parameters
+ # Path-only optimization: smooths geometric path (x,y positions)
+ # Velocity/acceleration are derived from smoothed positions in post-processing
+
+ # Optimization weights
+ weight_smoothness: 10.0 # Weight for path curvature minimization
+ weight_fidelity: 1.0 # Baseline fidelity (used when velocity-based disabled)
+
+ # Time discretization
+ time_step_s: 0.1 # Fixed time step for velocity/acceleration calculations [s]
+
+ # OSQP solver settings (tuned for real-time performance)
+ osqp_eps_abs: 1.0e-4 # Absolute tolerance for convergence
+ osqp_eps_rel: 1.0e-4 # Relative tolerance for convergence
+ osqp_max_iter: 100 # Maximum solver iterations
+ osqp_verbose: false # Print solver output to console
+
+ # Orientation preservation
+ preserve_input_trajectory_orientation: false # Copy orientations from input trajectory to smoothed output
+ max_distance_for_orientation_m: 5.0 # Max distance for nearest neighbor matching when copying orientations [m]
+
+ # Velocity-based fidelity weighting
+ use_velocity_based_fidelity: true # Enable velocity-dependent fidelity (low weight at slow speeds)
+ velocity_threshold_mps: 0.3 # Speed at which sigmoid transitions (midpoint) [m/s]
+ sigmoid_sharpness: 50.0 # Sigmoid steepness (higher = sharper transition)
+ min_fidelity_weight: 0.01 # Minimum fidelity at very low speeds
+ max_fidelity_weight: 1.0 # Maximum fidelity at high speeds
+
+ # Point constraints
+ num_constrained_points_start: 3 # Number of points from start to constrain (preserves initial state)
+ num_constrained_points_end: 0 # Number of points from end to constrain
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_spline_smoother.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_spline_smoother.param.yaml
new file mode 100644
index 0000000000..9121763368
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_spline_smoother.param.yaml
@@ -0,0 +1,7 @@
+/**:
+ ros__parameters:
+ trajectory_spline_smoother:
+ # Spline interpolation
+ interpolation_resolution_m: 0.2 # [m] Interpolation resolution for Akima spline
+ max_distance_discrepancy_m: 5.0 # [m] Maximum position deviation allowed for orientation copying
+ preserve_input_trajectory_orientation: false # Flag to indicate if orientation from original trajectory should be copied
diff --git a/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_velocity_optimizer.param.yaml b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_velocity_optimizer.param.yaml
new file mode 100644
index 0000000000..8cf7d32c2e
--- /dev/null
+++ b/autoware_launch/config/planning/neural_net_planner/trajectory_optimizer_plugins/trajectory_velocity_optimizer.param.yaml
@@ -0,0 +1,35 @@
+/**:
+ ros__parameters:
+ trajectory_velocity_optimizer:
+ # Trajectory matching thresholds
+ nearest_dist_threshold_m: 1.5 # [m] Distance threshold for trajectory matching
+ nearest_yaw_threshold_deg: 60.0 # [deg] Yaw threshold for trajectory matching
+
+ # Engage behavior
+ target_pull_out_speed_mps: 1.0 # [m/s] Target speed during pull-out maneuver
+ target_pull_out_acc_mps2: 1.0 # [m/s²] Target acceleration during pull-out
+ set_engage_speed: false # Set minimum speed during engage
+
+ # Speed limiting (uses external_velocity_limit topic to set max speed)
+ limit_speed: true # Enable speed limiting
+
+ # Lateral acceleration limiting
+ max_lateral_accel_mps2: 2.0 # [m/s²] Maximum lateral acceleration
+ limit_lateral_acceleration: false # Enable lateral acceleration limiting, should be launched with velocity smoother
+ min_limited_speed_mps: 3.0 # [m/s] Minimum speed when applying lateral acceleration limit
+
+ # Velocity smoothing
+ smooth_velocities: false # Enable jerk-filtered velocity smoothing
+
+ # Continuous jerk smoother settings
+ # Note: Kinematic limits (max_accel, min_decel, max_jerk, min_jerk) are loaded
+ # from the common namespace (limit.max_acc, limit.min_acc, limit.max_jerk, limit.min_jerk)
+ # Note: max_velocity uses max_speed_mps from parent namespace
+ continuous_jerk_smoother:
+ # QP optimization weights
+ jerk_weight: 30.0 # Weight for jerk minimization (smoothness)
+ over_v_weight: 3000.0 # Weight for velocity limit violation (slack)
+ over_a_weight: 30.0 # Weight for acceleration limit violation (slack)
+ over_j_weight: 10.0 # Weight for jerk limit violation (slack)
+ velocity_tracking_weight: 1.0 # Weight for tracking reference velocity from input trajectory
+ accel_tracking_weight: 300.0 # Weight for tracking reference acceleration from input trajectory
diff --git a/autoware_launch/config/system/diagnostics/autoware-main-e2e.yaml b/autoware_launch/config/system/diagnostics/autoware-main-e2e.yaml
new file mode 100644
index 0000000000..22a8deb865
--- /dev/null
+++ b/autoware_launch/config/system/diagnostics/autoware-main-e2e.yaml
@@ -0,0 +1,15 @@
+files:
+ - { path: $(dirname)/autoware-main.yaml }
+
+edits:
+ - { type: remove, path: /autoware/planning/trajectory_validation/finite }
+ - { type: remove, path: /autoware/planning/trajectory_validation/interval }
+ - { type: remove, path: /autoware/planning/trajectory_validation/curvature }
+ - { type: remove, path: /autoware/planning/trajectory_validation/angle }
+ - { type: remove, path: /autoware/planning/trajectory_validation/lateral_acceleration }
+ - { type: remove, path: /autoware/planning/trajectory_validation/acceleration }
+ - { type: remove, path: /autoware/planning/trajectory_validation/deceleration }
+ - { type: remove, path: /autoware/planning/trajectory_validation/steering }
+ - { type: remove, path: /autoware/planning/trajectory_validation/steering_rate }
+ - { type: remove, path: /autoware/planning/trajectory_validation/velocity_deviation }
+ - { type: remove, path: /autoware/planning/trajectory_validation/trajectory_shift }
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 184aa7e5ab..617075e39c 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -8,6 +8,7 @@
+
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index f4e24adf96..c725445fb0 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -6,11 +6,16 @@
+
+
+
+
+
@@ -121,5 +126,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/autoware_launch/launch/components/tier4_system_component.launch.xml b/autoware_launch/launch/components/tier4_system_component.launch.xml
index 65ac8bc9d2..a60ffb5d80 100644
--- a/autoware_launch/launch/components/tier4_system_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_system_component.launch.xml
@@ -1,8 +1,18 @@
+
-
+
+
diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz
index f69b1942f7..ab5d66e970 100644
--- a/autoware_launch/rviz/autoware.rviz
+++ b/autoware_launch/rviz/autoware.rviz
@@ -2109,6 +2109,98 @@ Visualization Manager:
Value: true
Enabled: true
Name: ScenarioPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DiffusionPlannerRouteMarker
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/debug/route_marker
+ Value: true
+ - Class: tier4_planning_factor_rviz_plugin/PlanningFactorRvizPlugin
+ Enabled: true
+ Name: PlanningFactor(DiffusionPlanner)
+ Namespaces:
+ {}
+ Show Safety Factors: false
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/planning_factors/diffusion_planner
+ Value: true
+ show_safety_factors: false
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/PredictedObjects
+ Confidence Interval: 95%
+ Display Acceleration: true
+ Display Existence Probability: false
+ Display Label: true
+ Display Pose Covariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display Twist Covariance: false
+ Display UUID: true
+ Display Velocity: true
+ Display Yaw Covariance: false
+ Display Yaw Rate: false
+ Display Yaw Rate Covariance: false
+ Enabled: true
+ Line Width: 0.10000000149011612
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: PredictedObjects
+ Namespaces:
+ acceleration: true
+ label: true
+ path: true
+ path confidence: true
+ position covariance: true
+ shape: true
+ twist: true
+ uuid: true
+ velocity: true
+ Object Fill Type: Fill
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/output/predicted_objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: true
+ Name: NeuralNetworkBasedPlanner
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/MarkerArray
diff --git a/autoware_launch/rviz/planning_bev.rviz b/autoware_launch/rviz/planning_bev.rviz
index 06766abc3d..e1a666f802 100644
--- a/autoware_launch/rviz/planning_bev.rviz
+++ b/autoware_launch/rviz/planning_bev.rviz
@@ -2156,6 +2156,98 @@ Visualization Manager:
Value: true
Enabled: true
Name: ScenarioPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DiffusionPlannerRouteMarker
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/debug/route_marker
+ Value: true
+ - Class: tier4_planning_factor_rviz_plugin/PlanningFactorRvizPlugin
+ Enabled: true
+ Name: PlanningFactor(DiffusionPlanner)
+ Namespaces:
+ {}
+ Show Safety Factors: false
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/planning_factors/diffusion_planner
+ Value: true
+ show_safety_factors: false
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/PredictedObjects
+ Confidence Interval: 95%
+ Display Acceleration: true
+ Display Existence Probability: false
+ Display Label: true
+ Display Pose Covariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display Twist Covariance: false
+ Display UUID: true
+ Display Velocity: true
+ Display Yaw Covariance: false
+ Display Yaw Rate: false
+ Display Yaw Rate Covariance: false
+ Enabled: true
+ Line Width: 0.10000000149011612
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: PredictedObjects
+ Namespaces:
+ acceleration: true
+ label: true
+ path: true
+ path confidence: true
+ position covariance: true
+ shape: true
+ twist: true
+ uuid: true
+ velocity: true
+ Object Fill Type: Fill
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/output/predicted_objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: true
+ Name: NeuralNetworkBasedPlanner
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/MarkerArray
diff --git a/autoware_launch/rviz/planning_tpv.rviz b/autoware_launch/rviz/planning_tpv.rviz
index a964576633..1824b89ce3 100644
--- a/autoware_launch/rviz/planning_tpv.rviz
+++ b/autoware_launch/rviz/planning_tpv.rviz
@@ -2155,6 +2155,98 @@ Visualization Manager:
Value: true
Enabled: true
Name: ScenarioPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DiffusionPlannerRouteMarker
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/debug/route_marker
+ Value: true
+ - Class: tier4_planning_factor_rviz_plugin/PlanningFactorRvizPlugin
+ Enabled: true
+ Name: PlanningFactor(DiffusionPlanner)
+ Namespaces:
+ {}
+ Show Safety Factors: false
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/planning_factors/diffusion_planner
+ Value: true
+ show_safety_factors: false
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/PredictedObjects
+ Confidence Interval: 95%
+ Display Acceleration: true
+ Display Existence Probability: false
+ Display Label: true
+ Display Pose Covariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display Twist Covariance: false
+ Display UUID: true
+ Display Velocity: true
+ Display Yaw Covariance: false
+ Display Yaw Rate: false
+ Display Yaw Rate Covariance: false
+ Enabled: true
+ Line Width: 0.10000000149011612
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: PredictedObjects
+ Namespaces:
+ acceleration: true
+ label: true
+ path: true
+ path confidence: true
+ position covariance: true
+ shape: true
+ twist: true
+ uuid: true
+ velocity: true
+ Object Fill Type: Fill
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/output/predicted_objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: true
+ Name: NeuralNetworkBasedPlanner
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/MarkerArray
diff --git a/autoware_launch/rviz/scenario_simulator.rviz b/autoware_launch/rviz/scenario_simulator.rviz
index 6461fd0bed..19b48c7cf2 100644
--- a/autoware_launch/rviz/scenario_simulator.rviz
+++ b/autoware_launch/rviz/scenario_simulator.rviz
@@ -2690,6 +2690,98 @@ Visualization Manager:
Value: true
Enabled: true
Name: ScenarioPlanning
+ - Class: rviz_common/Group
+ Displays:
+ - Class: rviz_default_plugins/MarkerArray
+ Enabled: true
+ Name: DiffusionPlannerRouteMarker
+ Namespaces:
+ {}
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/debug/route_marker
+ Value: true
+ - Class: tier4_planning_factor_rviz_plugin/PlanningFactorRvizPlugin
+ Enabled: true
+ Name: PlanningFactor(DiffusionPlanner)
+ Namespaces:
+ {}
+ Show Safety Factors: false
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Value: /planning/planning_factors/diffusion_planner
+ Value: true
+ show_safety_factors: false
+ - BUS:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CAR:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ CYCLIST:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Class: autoware_perception_rviz_plugin/PredictedObjects
+ Confidence Interval: 95%
+ Display Acceleration: true
+ Display Existence Probability: false
+ Display Label: true
+ Display Pose Covariance: true
+ Display Predicted Path Confidence: true
+ Display Predicted Paths: true
+ Display Twist: true
+ Display Twist Covariance: false
+ Display UUID: true
+ Display Velocity: true
+ Display Yaw Covariance: false
+ Display Yaw Rate: false
+ Display Yaw Rate Covariance: false
+ Enabled: true
+ Line Width: 0.10000000149011612
+ MOTORCYCLE:
+ Alpha: 0.9990000128746033
+ Color: 119; 11; 32
+ Name: PredictedObjects
+ Namespaces:
+ acceleration: true
+ label: true
+ path: true
+ path confidence: true
+ position covariance: true
+ shape: true
+ twist: true
+ uuid: true
+ velocity: true
+ Object Fill Type: Fill
+ PEDESTRIAN:
+ Alpha: 0.9990000128746033
+ Color: 255; 192; 203
+ Polygon Type: 3d
+ TRAILER:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ TRUCK:
+ Alpha: 0.9990000128746033
+ Color: 30; 144; 255
+ Topic:
+ Depth: 5
+ Durability Policy: Volatile
+ History Policy: Keep Last
+ Reliability Policy: Best Effort
+ Value: /planning/trajectory_generator/neural_network_based_planner/diffusion_planner_node/output/predicted_objects
+ UNKNOWN:
+ Alpha: 0.9990000128746033
+ Color: 255; 255; 255
+ Value: true
+ Visualization Type: Normal
+ Enabled: true
+ Name: NeuralNetworkBasedPlanner
- Class: rviz_common/Group
Displays:
- Class: rviz_default_plugins/MarkerArray
diff --git a/tier4_universe_launch/tier4_planning_launch/launch/learning_based_planning/diffusion_planner.launch.xml b/tier4_universe_launch/tier4_planning_launch/launch/learning_based_planning/diffusion_planner.launch.xml
new file mode 100644
index 0000000000..04cbd394c6
--- /dev/null
+++ b/tier4_universe_launch/tier4_planning_launch/launch/learning_based_planning/diffusion_planner.launch.xml
@@ -0,0 +1,77 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/tier4_universe_launch/tier4_planning_launch/launch/planning.launch.xml b/tier4_universe_launch/tier4_planning_launch/launch/planning.launch.xml
index a1c14eea9f..c50d1678a5 100644
--- a/tier4_universe_launch/tier4_planning_launch/launch/planning.launch.xml
+++ b/tier4_universe_launch/tier4_planning_launch/launch/planning.launch.xml
@@ -37,7 +37,7 @@
-
+
@@ -47,11 +47,36 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
+
@@ -65,7 +90,28 @@
-
+
+
+
+
+
+
+
+
+
+