diff --git a/autoware_launch/config/tools/autoware_bag_recorder/autoware_bag_recorder.param.yaml b/autoware_launch/config/tools/autoware_bag_recorder/autoware_bag_recorder.param.yaml
new file mode 100644
index 0000000000..f612b3740f
--- /dev/null
+++ b/autoware_launch/config/tools/autoware_bag_recorder/autoware_bag_recorder.param.yaml
@@ -0,0 +1,545 @@
+/**:
+ ros__parameters:
+ common:
+ database_storage: "sqlite3" # sqlite3 or mcap
+ maximum_record_time: 36000 # seconds
+ maximum_allowed_bag_storage_size: 500.0 # GB
+ maximum_bag_file_size: 20.0 # GB
+ enable_only_auto_mode_recording: false # if enabled, recording occurs only "AUTO" mode
+ record_all_topic_in_a_bag: true # creates single bag file with all sections
+ number_of_maximum_bags: 1000 # limit of stored bag file count
+ path: "bags/" # Path to bag file for saving
+ minimum_acceptable_disk_space: 50 # GB
+ disk_space_threshold_action: "shutdown" # [remove, shutdown] remove files or shutdown node
+ api_modules:
+ record_api: false
+ api_topics:
+ - /api/autoware/get/emergency
+ - /api/autoware/get/engage
+ - /api/autoware/get/map/info/hash
+ - /api/external/get/command/selected/control
+ - /api/external/get/rtc_status
+ - /api/external/set/command/local/control
+ - /api/external/set/command/local/heartbeat
+ - /api/external/set/command/local/shift
+ - /api/external/set/command/local/turn_signal
+ - /api/external/set/command/remote/control
+ - /api/external/set/command/remote/heartbeat
+ - /api/external/set/command/remote/shift
+ - /api/external/set/command/remote/turn_signal
+ - /api/fail_safe/mrm_state
+ - /api/localization/initialization_state
+ - /api/motion/state
+ - /api/operation_mode/state
+ - /api/perception/objects
+ - /api/planning/steering_factors
+ - /api/planning/velocity_factors
+ - /api/routing/route
+ - /api/routing/state
+ - /api/vehicle/kinematics
+ - /api/vehicle/status
+ autoware_modules:
+ record_autoware: false
+ autoware_topics:
+ - /autoware/engage
+ - /autoware/state
+ - /autoware_orientation
+ control_modules:
+ record_control: false
+ control_topics:
+ - /control/command/control_cmd
+ - /control/command/emergency_cmd
+ - /control/command/gear_cmd
+ - /control/command/hazard_lights_cmd
+ - /control/command/turn_indicators_cmd
+ - /control/control_validator/debug/marker
+ - /control/control_validator/output/markers
+ - /control/control_validator/validation_status
+ - /control/control_validator/virtual_wall
+ - /control/current_gate_mode
+ - /control/external_cmd_selector/current_selector_mode
+ - /control/gate_mode_cmd
+ - /control/operation_mode_transition_manager/debug_info
+ - /control/shift_decider/gear_cmd
+ - /control/trajectory_follower/control_cmd
+ - /control/trajectory_follower/controller_node_exe/output/debug_marker
+ - /control/trajectory_follower/controller_node_exe/output/estimated_steer_offset
+ - /control/trajectory_follower/lane_departure_checker_node/debug/processing_time_ms
+ - /control/trajectory_follower/lateral/diagnostic
+ - /control/trajectory_follower/lateral/predicted_trajectory
+ - /control/trajectory_follower/longitudinal/diagnostic
+ - /control/trajectory_follower/longitudinal/slope_angle
+ - /control/vehicle_cmd_gate/is_paused
+ - /control/vehicle_cmd_gate/is_start_requested
+ - /control/vehicle_cmd_gate/is_stopped
+ - /control/vehicle_cmd_gate/operation_mode
+ external_modules:
+ record_external: false
+ external_topics:
+ - /external/selected/control_cmd
+ - /external/selected/external_control_cmd
+ - /external/selected/gear_cmd
+ - /external/selected/hazard_lights_cmd
+ - /external/selected/heartbeat
+ - /external/selected/turn_indicators_cmd
+ localization_modules:
+ record_localization: false
+ localization_topics:
+ - /initialpose
+ - /initialpose3d
+ - /localization/acceleration
+ - /localization/debug/ellipse_marker
+ - /localization/initialization_state
+ - /localization/kinematic_state
+ - /localization/pose_estimator/debug/loaded_pointcloud_map
+ - /localization/pose_estimator/exe_time_ms
+ - /localization/pose_estimator/initial_pose_with_covariance
+ - /localization/pose_estimator/initial_to_result_distance
+ - /localization/pose_estimator/initial_to_result_distance_new
+ - /localization/pose_estimator/initial_to_result_distance_old
+ - /localization/pose_estimator/iteration_num
+ - /localization/pose_estimator/monte_carlo_initial_pose_marker
+ - /localization/pose_estimator/ndt_marker
+ - /localization/pose_estimator/nearest_voxel_transformation_likelihood
+ - /localization/pose_estimator/no_ground_nearest_voxel_transformation_likelihood
+ - /localization/pose_estimator/no_ground_transform_probability
+ - /localization/pose_estimator/points_aligned
+ - /localization/pose_estimator/points_aligned_no_ground
+ - /localization/pose_estimator/pose
+ - /localization/pose_estimator/pose_with_covariance
+ - /localization/pose_estimator/transform_probability
+ - /localization/pose_twist_fusion_filter/biased_pose
+ - /localization/pose_twist_fusion_filter/biased_pose_with_covariance
+ - /localization/pose_twist_fusion_filter/debug
+ - /localization/pose_twist_fusion_filter/debug/measured_pose
+ - /localization/pose_twist_fusion_filter/debug/stop_flag
+ - /localization/pose_twist_fusion_filter/estimated_yaw_bias
+ - /localization/pose_twist_fusion_filter/kinematic_state
+ - /localization/pose_twist_fusion_filter/pose
+ - /localization/pose_twist_fusion_filter/twist
+ - /localization/pose_twist_fusion_filter/twist_with_covariance
+ - /localization/pose_with_covariance
+ - /localization/twist_estimator/gyro_twist
+ - /localization/twist_estimator/gyro_twist_raw
+ - /localization/twist_estimator/twist_with_covariance
+ - /localization/twist_estimator/twist_with_covariance_raw
+ - /localization/util/crop_box_filter/debug/cyclic_time_ms
+ - /localization/util/crop_box_filter/debug/processing_time_ms
+ - /localization/util/crop_box_filter_measurement_range/crop_box_polygon
+ - /localization/util/downsample/pointcloud
+ - /localization/util/measurement_range/pointcloud
+ - /localization/util/voxel_grid_downsample/pointcloud
+ map_modules:
+ record_map: false
+ map_topics:
+ - /map/map_projector_type
+ - /map/pointcloud_map
+ - /map/vector_map
+ - /map/vector_map_marker
+ perception_modules:
+ record_perception: false
+ perception_topics:
+ - /perception/object_recognition/detection/centerpoint/lidar_centerpoint/debug/cyclic_time_ms
+ - /perception/object_recognition/detection/centerpoint/lidar_centerpoint/debug/processing_time_ms
+ - /perception/object_recognition/detection/centerpoint/objects
+ - /perception/object_recognition/detection/centerpoint/validation/objects
+ - /perception/object_recognition/detection/clustering/clusters
+ - /perception/object_recognition/detection/clustering/debug/clusters
+ - /perception/object_recognition/detection/clustering/objects
+ - /perception/object_recognition/detection/clustering/objects_with_feature
+ - /perception/object_recognition/detection/debug/downsampled_map/pointcloud
+ - /perception/object_recognition/detection/detection_by_tracker/debug/divided_objects
+ - /perception/object_recognition/detection/detection_by_tracker/debug/initial_objects
+ - /perception/object_recognition/detection/detection_by_tracker/debug/merged_objects
+ - /perception/object_recognition/detection/detection_by_tracker/debug/tracked_objects
+ - /perception/object_recognition/detection/detection_by_tracker/objects
+ - /perception/object_recognition/detection/objects
+ - /perception/object_recognition/detection/objects_before_filter
+ - /perception/object_recognition/detection/pointcloud_map_filtered/pointcloud
+ - /perception/object_recognition/detection/temporary_merged_objects
+ - /perception/object_recognition/detection/voxel_based_compare_map_filter/debug/cyclic_time_ms
+ - /perception/object_recognition/detection/voxel_based_compare_map_filter/debug/processing_time_ms
+ - /perception/object_recognition/objects
+ - /perception/object_recognition/prediction/maneuver
+ - /perception/object_recognition/prediction/map_based_prediction/debug/calculation_time
+ - /perception/object_recognition/tracking/objects
+ - /perception/obstacle_segmentation/crop_box_filter/crop_box_polygon
+ - /perception/obstacle_segmentation/crop_box_filter/debug/cyclic_time_ms
+ - /perception/obstacle_segmentation/crop_box_filter/debug/processing_time_ms
+ - /perception/obstacle_segmentation/occupancy_grid_map_outlier_filter/debug/cyclic_time_ms
+ - /perception/obstacle_segmentation/occupancy_grid_map_outlier_filter/debug/processing_time_ms
+ - /perception/obstacle_segmentation/pointcloud
+ - /perception/obstacle_segmentation/range_cropped/pointcloud
+ - /perception/obstacle_segmentation/scan_ground_filter/debug/cyclic_time_ms
+ - /perception/obstacle_segmentation/scan_ground_filter/debug/processing_time_ms
+ - /perception/obstacle_segmentation/single_frame/pointcloud_raw
+ - /perception/occupancy_grid_map/map
+ - /perception/occupancy_grid_map/map_updates
+ - /perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map/debug/cyclic_time_ms
+ - /perception/occupancy_grid_map/pointcloud_based_occupancy_grid_map/debug/processing_time_ms
+ - /perception/traffic_light_recognition/camera6/camera_info
+ - /perception/traffic_light_recognition/camera6/classification/classified/traffic_signals
+ - /perception/traffic_light_recognition/camera6/classification/estimated/traffic_signals
+ - /perception/traffic_light_recognition/camera6/classification/traffic_light_classifier/output/debug/image
+ - /perception/traffic_light_recognition/camera6/classification/traffic_light_classifier/output/debug/image/compressed
+ - /perception/traffic_light_recognition/camera6/classification/traffic_light_classifier/output/debug/image/compressedDepth
+ - /perception/traffic_light_recognition/camera6/classification/traffic_light_classifier/output/debug/image/theora
+ - /perception/traffic_light_recognition/camera6/classification/traffic_signals
+ - /perception/traffic_light_recognition/camera6/debug/rois
+ - /perception/traffic_light_recognition/camera6/debug/rois/compressed
+ - /perception/traffic_light_recognition/camera6/debug/rois/compressedDepth
+ - /perception/traffic_light_recognition/camera6/debug/rois/theora
+ - /perception/traffic_light_recognition/camera6/detection/expect/rois
+ - /perception/traffic_light_recognition/camera6/detection/rois
+ - /perception/traffic_light_recognition/camera6/detection/rough/rois
+ - /perception/traffic_light_recognition/camera6/detection/traffic_light_fine_detector/debug/exe_time_ms
+ - /perception/traffic_light_recognition/camera6/detection/traffic_light_map_based_detector/debug/markers
+ - /perception/traffic_light_recognition/external/traffic_signals
+ - /perception/traffic_light_recognition/internal/traffic_signals
+ - /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers
+ - /perception/traffic_light_recognition/traffic_signals
+ - /perception/traffic_light_recognition/traffic_signals/markers
+ planning_modules:
+ record_planning: false
+ planning_topics:
+ - /planning/cooperate_status/avoidance_by_lane_change_left
+ - /planning/cooperate_status/avoidance_by_lane_change_right
+ - /planning/cooperate_status/avoidance_left
+ - /planning/cooperate_status/avoidance_right
+ - /planning/cooperate_status/blind_spot
+ - /planning/cooperate_status/crosswalk
+ - /planning/cooperate_status/detection_area
+ - /planning/cooperate_status/external_request_lane_change_left
+ - /planning/cooperate_status/external_request_lane_change_right
+ - /planning/cooperate_status/goal_planner
+ - /planning/cooperate_status/intersection
+ - /planning/cooperate_status/intersection_occlusion
+ - /planning/cooperate_status/lane_change_left
+ - /planning/cooperate_status/lane_change_right
+ - /planning/cooperate_status/no_stopping_area
+ - /planning/cooperate_status/occlusion_spot
+ - /planning/cooperate_status/start_planner
+ - /planning/cooperate_status/traffic_light
+ - /planning/cooperate_status/virtual_traffic_light
+ - /planning/hazard_lights_cmd
+ - /planning/mission_planning/checkpoint
+ - /planning/mission_planning/debug/goal_footprint
+ - /planning/mission_planning/echo_back_goal_pose
+ - /planning/mission_planning/goal
+ - /planning/mission_planning/mrm_route
+ - /planning/mission_planning/normal_route
+ - /planning/mission_planning/route
+ - /planning/mission_planning/route_marker
+ - /planning/mission_planning/route_state
+ - /planning/path_candidate/avoidance
+ - /planning/path_candidate/avoidance_by_lane_change
+ - /planning/path_candidate/external_request_lane_change_left
+ - /planning/path_candidate/external_request_lane_change_right
+ - /planning/path_candidate/goal_planner
+ - /planning/path_candidate/lane_change
+ - /planning/path_candidate/lane_change_left
+ - /planning/path_candidate/lane_change_right
+ - /planning/path_candidate/side_shift
+ - /planning/path_candidate/start_planner
+ - /planning/path_reference/avoidance
+ - /planning/path_reference/avoidance_by_lane_change
+ - /planning/path_reference/goal_planner
+ - /planning/path_reference/lane_change_left
+ - /planning/path_reference/lane_change_right
+ - /planning/path_reference/side_shift
+ - /planning/path_reference/start_planner
+ - /planning/planning_validator/debug/marker
+ - /planning/planning_validator/output/markers
+ - /planning/planning_validator/validation_status
+ - /planning/planning_validator/virtual_wall
+ - /planning/scenario_planning/clear_velocity_limit
+ - /planning/scenario_planning/current_max_velocity
+ - /planning/scenario_planning/external_velocity_limit_selector/debug
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance_by_lane_change
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance_debug_message_array
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/goal_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_debug_message_array
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_right
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/side_shift
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/start_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/turn_signal_info
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/avoidance
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/avoidance_by_lane_change
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/goal_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/lane_change_left
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/lane_change_right
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/side_shift
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_lanes/start_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance_by_lane_change
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/goal_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_left
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_right
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/side_shift
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/start_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/input/lateral_offset
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/maximum_drivable_area
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/is_reroute_available
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance_by_lane_change
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_left
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_right
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/goal_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_left
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_right
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/side_shift
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/start_planner
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/merge_from_private
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/merge_from_private/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/out_of_lane
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/out_of_lane/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/walkway
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/walkway/processing_time_ms
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/output/stop_reason
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/blind_spot
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/detection_area
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/intersection
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/merge_from_private
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_stopping_area
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/occlusion_spot
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/out_of_lane
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/run_out
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/speed_bump
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/stop_line
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/traffic_light
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/virtual_traffic_light
+ - /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/walkway
+ - /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal
+ - /planning/scenario_planning/lane_driving/behavior_planning/output/auto_mode_statuses
+ - /planning/scenario_planning/lane_driving/behavior_planning/path
+ - /planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id
+ - /planning/scenario_planning/lane_driving/motion_planning/debug_markers
+ - /planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/debug/calculation_time
+ - /planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/debug/eb_fixed_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/debug/eb_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/debug/extended_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/elastic_band_smoother/output/traj
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/calculation_time
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/extended_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_fixed_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_ref_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/mpt_traj
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/virtual_wall
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/adaptive_cruise_control/debug_values
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/collision_pointcloud
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/obstacle_pointcloud
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/input/expand_stop_range
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop/debug_values
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/output/runtime_microseconds
+ - /planning/scenario_planning/lane_driving/motion_planning/obstacle_velocity_limiter/trajectory
+ - /planning/scenario_planning/lane_driving/motion_planning/path_smoother/path
+ - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint
+ - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_offset
+ - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_recover_offset
+ - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker
+ - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall
+ - /planning/scenario_planning/lane_driving/trajectory
+ - /planning/scenario_planning/max_velocity
+ - /planning/scenario_planning/max_velocity_candidates
+ - /planning/scenario_planning/max_velocity_default
+ - /planning/scenario_planning/modified_goal
+ - /planning/scenario_planning/motion_velocity_smoother/calculation_time
+ - /planning/scenario_planning/motion_velocity_smoother/closest_acceleration
+ - /planning/scenario_planning/motion_velocity_smoother/closest_jerk
+ - /planning/scenario_planning/motion_velocity_smoother/closest_max_velocity
+ - /planning/scenario_planning/motion_velocity_smoother/closest_merged_velocity
+ - /planning/scenario_planning/motion_velocity_smoother/closest_velocity
+ - /planning/scenario_planning/motion_velocity_smoother/debug/backward_filtered_trajectory
+ - /planning/scenario_planning/motion_velocity_smoother/debug/forward_filtered_trajectory
+ - /planning/scenario_planning/motion_velocity_smoother/debug/merged_filtered_trajectory
+ - /planning/scenario_planning/motion_velocity_smoother/debug/trajectory_external_velocity_limited
+ - /planning/scenario_planning/motion_velocity_smoother/debug/trajectory_lateral_acc_filtered
+ - /planning/scenario_planning/motion_velocity_smoother/debug/trajectory_raw
+ - /planning/scenario_planning/motion_velocity_smoother/debug/trajectory_steering_rate_limited
+ - /planning/scenario_planning/motion_velocity_smoother/debug/trajectory_time_resampled
+ - /planning/scenario_planning/motion_velocity_smoother/distance_to_stopline
+ - /planning/scenario_planning/motion_velocity_smoother/stop_speed_exceeded
+ - /planning/scenario_planning/motion_velocity_smoother/trajectory
+ - /planning/scenario_planning/parking/costmap_generator/grid_map
+ - /planning/scenario_planning/parking/costmap_generator/occupancy_grid
+ - /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array
+ - /planning/scenario_planning/parking/freespace_planner/debug/pose_array
+ - /planning/scenario_planning/parking/is_completed
+ - /planning/scenario_planning/parking/trajectory
+ - /planning/scenario_planning/scenario
+ - /planning/scenario_planning/scenario_selector/trajectory
+ - /planning/scenario_planning/status/infrastructure_commands
+ - /planning/scenario_planning/status/no_start_reason
+ - /planning/scenario_planning/status/stop_reason
+ - /planning/scenario_planning/status/stop_reasons
+ - /planning/scenario_planning/trajectory
+ - /planning/steering_factor/avoidance
+ - /planning/steering_factor/avoidance_by_lane_change
+ - /planning/steering_factor/goal_planner
+ - /planning/steering_factor/intersection
+ - /planning/steering_factor/lane_change
+ - /planning/steering_factor/lane_change_left
+ - /planning/steering_factor/lane_change_right
+ - /planning/steering_factor/side_shift
+ - /planning/steering_factor/start_planner
+ - /planning/turn_indicators_cmd
+ - /planning/velocity_factors/blind_spot
+ - /planning/velocity_factors/crosswalk
+ - /planning/velocity_factors/detection_area
+ - /planning/velocity_factors/intersection
+ - /planning/velocity_factors/merge_from_private
+ - /planning/velocity_factors/no_stopping_area
+ - /planning/velocity_factors/obstacle_cruise
+ - /planning/velocity_factors/obstacle_stop
+ - /planning/velocity_factors/occlusion_spot
+ - /planning/velocity_factors/out_of_lane
+ - /planning/velocity_factors/stop_line
+ - /planning/velocity_factors/surround_obstacle
+ - /planning/velocity_factors/traffic_light
+ - /planning/velocity_factors/virtual_traffic_light
+ - /planning/velocity_factors/walkway
+ sensing_modules:
+ record_sensing: false
+ sensing_topics:
+ - /sensing/camera/camera6/camera_info
+ - /sensing/camera/camera6/image_raw
+ - /sensing/camera/camera6/image_raw/compressed
+ - /sensing/gnss/fixed
+ - /sensing/gnss/pose
+ - /sensing/gnss/pose_with_covariance
+ - /sensing/gnss/ublox/fix_velocity
+ - /sensing/gnss/ublox/nav_sat_fix
+ - /sensing/gnss/ublox/navpvt
+ - /sensing/imu/imu_data
+ - /sensing/imu/tamagawa/imu_raw
+ - /sensing/lidar/concatenate_data_synchronizer/debug/cyclic_time_ms
+ - /sensing/lidar/concatenate_data_synchronizer/debug/processing_time_ms
+ - /sensing/lidar/concatenated/pointcloud
+ # /sensing/lidar/left/crop_box_filter/debug/cyclic_time_ms
+ # /sensing/lidar/left/crop_box_filter/debug/processing_time_ms
+ # /sensing/lidar/left/crop_box_filter_mirror/crop_box_polygon
+ # /sensing/lidar/left/crop_box_filter_self/crop_box_polygon
+ # /sensing/lidar/left/distortion_corrector/debug/cyclic_time_ms
+ # /sensing/lidar/left/distortion_corrector/debug/processing_time_ms
+ # /sensing/lidar/left/mirror_cropped/pointcloud_ex
+ # /sensing/lidar/left/outlier_filtered/pointcloud
+ # /sensing/lidar/left/outlier_filtered/pointcloud_synchronized
+ # /sensing/lidar/left/pointcloud_raw
+ # /sensing/lidar/left/pointcloud_raw_ex
+ # /sensing/lidar/left/rectified/pointcloud_ex
+ # /sensing/lidar/left/ring_outlier_filter/debug/cyclic_time_ms
+ # /sensing/lidar/left/ring_outlier_filter/debug/processing_time_ms
+ # /sensing/lidar/left/self_cropped/pointcloud_ex
+ # /sensing/lidar/left/velodyne_model_marker
+ # /sensing/lidar/left/velodyne_packets
+ # /sensing/lidar/rear/crop_box_filter_mirror/crop_box_polygon
+ # /sensing/lidar/rear/crop_box_filter_self/crop_box_polygon
+ # /sensing/lidar/rear/mirror_cropped/pointcloud_ex
+ # /sensing/lidar/rear/outlier_filtered/pointcloud
+ # /sensing/lidar/rear/pointcloud_raw
+ # /sensing/lidar/rear/pointcloud_raw_ex
+ # /sensing/lidar/rear/rectified/pointcloud_ex
+ # /sensing/lidar/rear/self_cropped/pointcloud_ex
+ # /sensing/lidar/rear/velodyne_model_marker
+ # /sensing/lidar/rear/velodyne_packets
+ # /sensing/lidar/right/crop_box_filter/debug/cyclic_time_ms
+ # /sensing/lidar/right/crop_box_filter/debug/processing_time_ms
+ # /sensing/lidar/right/crop_box_filter_mirror/crop_box_polygon
+ # /sensing/lidar/right/crop_box_filter_self/crop_box_polygon
+ # /sensing/lidar/right/distortion_corrector/debug/cyclic_time_ms
+ # /sensing/lidar/right/distortion_corrector/debug/processing_time_ms
+ # /sensing/lidar/right/mirror_cropped/pointcloud_ex
+ # /sensing/lidar/right/outlier_filtered/pointcloud
+ # /sensing/lidar/right/outlier_filtered/pointcloud_synchronized
+ # /sensing/lidar/right/pointcloud_raw
+ # /sensing/lidar/right/pointcloud_raw_ex
+ # /sensing/lidar/right/rectified/pointcloud_ex
+ # /sensing/lidar/right/ring_outlier_filter/debug/cyclic_time_ms
+ # /sensing/lidar/right/ring_outlier_filter/debug/processing_time_ms
+ # /sensing/lidar/right/self_cropped/pointcloud_ex
+ # /sensing/lidar/right/velodyne_model_marker
+ # /sensing/lidar/right/velodyne_packets
+ # /sensing/lidar/top/crop_box_filter/debug/cyclic_time_ms
+ # /sensing/lidar/top/crop_box_filter/debug/processing_time_ms
+ # /sensing/lidar/top/crop_box_filter_mirror/crop_box_polygon
+ # /sensing/lidar/top/crop_box_filter_self/crop_box_polygon
+ # /sensing/lidar/top/distortion_corrector/debug/cyclic_time_ms
+ # /sensing/lidar/top/distortion_corrector/debug/processing_time_ms
+ # /sensing/lidar/top/mirror_cropped/pointcloud_ex
+ # /sensing/lidar/top/outlier_filtered/pointcloud
+ # /sensing/lidar/top/outlier_filtered/pointcloud_synchronized
+ # /sensing/lidar/top/pointcloud_raw
+ # /sensing/lidar/top/pointcloud_raw_ex
+ # /sensing/lidar/top/rectified/pointcloud_ex
+ # /sensing/lidar/top/ring_outlier_filter/debug/cyclic_time_ms
+ # /sensing/lidar/top/ring_outlier_filter/debug/processing_time_ms
+ # /sensing/lidar/top/self_cropped/pointcloud_ex
+ # /sensing/lidar/top/velodyne_model_marker
+ # /sensing/lidar/top/velodyne_packets
+ - /sensing/vehicle_velocity_converter/twist_with_covariance
+ system_modules:
+ record_system: false
+ system_topics:
+ - /system/component_state_monitor/component/autonomous/control
+ - /system/component_state_monitor/component/autonomous/localization
+ - /system/component_state_monitor/component/autonomous/map
+ - /system/component_state_monitor/component/autonomous/perception
+ - /system/component_state_monitor/component/autonomous/planning
+ - /system/component_state_monitor/component/autonomous/sensing
+ - /system/component_state_monitor/component/autonomous/system
+ - /system/component_state_monitor/component/autonomous/vehicle
+ - /system/component_state_monitor/component/launch/control
+ - /system/component_state_monitor/component/launch/localization
+ - /system/component_state_monitor/component/launch/map
+ - /system/component_state_monitor/component/launch/perception
+ - /system/component_state_monitor/component/launch/planning
+ - /system/component_state_monitor/component/launch/sensing
+ - /system/component_state_monitor/component/launch/system
+ - /system/component_state_monitor/component/launch/vehicle
+ - /system/emergency/control_cmd
+ - /system/emergency/gear_cmd
+ - /system/emergency/hazard_lights_cmd
+ - /system/emergency/hazard_status
+ - /system/emergency_handler/output/control_command
+ - /system/fail_safe/mrm_state
+ - /system/mrm/comfortable_stop/status
+ - /system/mrm/emergency_stop/status
+ - /system/operation_mode/state
+ vehicle_modules:
+ record_vehicle: false
+ vehicle_topics:
+ - /joint_states
+ - /robot_description
+ - /tf
+ - /tf_static
+ - /vehicle/status/battery_charge
+ - /vehicle/status/control_mode
+ - /vehicle/status/gear_status
+ - /vehicle/status/hazard_lights_status
+ - /vehicle/status/steering_status
+ - /vehicle/status/turn_indicators_status
+ - /vehicle/status/velocity_status
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index 1a4fbb70f4..310427ad8d 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -36,6 +36,7 @@
+
@@ -118,5 +119,8 @@
if="$(var rviz)"
respawn="$(var rviz_respawn)"
/>
+
+
+