Skip to content

Commit

Permalink
feat(launch): create booars launch (#19)
Browse files Browse the repository at this point in the history
* create booars_launch

Signed-off-by: Autumn60 <[email protected]>

* replace reference.launch.xml to booars.launch.xml

Signed-off-by: Autumn60 <[email protected]>

* update CODEOWNERS

Signed-off-by: Autumn60 <[email protected]>

---------

Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 authored Aug 24, 2024
1 parent 1859c6a commit 0ea6e14
Show file tree
Hide file tree
Showing 15 changed files with 6,385 additions and 5 deletions.
1 change: 1 addition & 0 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
aichallenge/workspace/src/aichallenge_submit/aichallenge_submit_launch/** @booars/aic2024-developers
aichallenge/workspace/src/aichallenge_submit/booars_launch/** @Autumn60
aichallenge/workspace/src/aichallenge_submit/booars_utils/** @Autumn60
aichallenge/workspace/src/aichallenge_submit/goal_pose_setter/** @hrjp
aichallenge/workspace/src/aichallenge_submit/gyro_odometer/** @booars/aic2024-developers
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,7 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<log message="This is aichallenge_submit_launch."/>
<include file="$(find-pkg-share aichallenge_submit_launch)/launch/reference.launch.xml" >
<arg name="vehicle_model" value="racing_kart"/>
<arg name="sensor_model" value="racing_kart_sensor_kit"/>
<arg name="map_path" value="$(find-pkg-share aichallenge_submit_launch)/map"/>
</include>
<include file="$(find-pkg-share booars_launch)/launch/booars.launch.xml" />

<!-- place a goal pose anywhere you like-->
<node pkg="goal_pose_setter" exec="goal_pose_setter_node" name="goal_pose_setter" output="screen">
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 3.5)
project(booars_launch)

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()
ament_auto_package(INSTALL_TO_SHARE launch map config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
angular_velocity_offset_x: 0.0 # [rad/s]
angular_velocity_offset_y: 0.0 # [rad/s]
angular_velocity_offset_z: 0.0 # [rad/s]
angular_velocity_stddev_xx: 0.03 # [rad/s]
angular_velocity_stddev_yy: 0.03 # [rad/s]
angular_velocity_stddev_zz: 0.03 # [rad/s]
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- Essential parameters -->
<arg name="use_sim_time" default="true"/>

<arg name="map_path" default="$(find-pkg-share booars_launch)/map"/>

<arg name="vehicle_model" default="racing_kart" description="vehicle model name"/>
<arg name="sensor_model" default="racing_kart_sensor_kit" description="sensor model name"/>

<!-- Optional parameters -->
<arg name="lanelet2_file" default="lanelet2_map.osm" description="lanelet2 map file name"/>

<!-- Common -->
<include file="$(find-pkg-share booars_launch)/launch/components/common.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="vehicle_model" value="$(var vehicle_model)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>
</include>

<!-- Map -->
<include file="$(find-pkg-share booars_launch)/launch/components/map.launch.xml">
<arg name="map_path" value="$(var map_path)"/>
<arg name="lanelet2_map_file" value="$(var lanelet2_file)"/>
</include>

<!-- Sensing -->
<include file="$(find-pkg-share booars_launch)/launch/components/sensing.launch.xml"/>

<!-- Perception -->
<include file="$(find-pkg-share booars_launch)/launch/components/perception.launch.xml"/>

<!-- Localization -->
<include file="$(find-pkg-share booars_launch)/launch/components/localization.launch.xml"/>

<!-- Planning -->
<include file="$(find-pkg-share booars_launch)/launch/components/planning.launch.xml"/>

<!-- Control -->
<include file="$(find-pkg-share booars_launch)/launch/components/control.launch.xml"/>

<!-- Vehicle -->
<include file="$(find-pkg-share booars_launch)/launch/components/vehicle.launch.xml"/>

<!-- API -->
<group>
<!-- default_ad_api -->
<include file="$(find-pkg-share default_ad_api)/launch/default_ad_api.launch.py" />

<!-- ad_api_adaptors -->
<include file="$(find-pkg-share ad_api_adaptors)/launch/rviz_adaptors.launch.xml" />
</group>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>

<!-- Parameters -->
<arg name="use_sim_time" description="use_sim_time"/>
<arg name="vehicle_model" description="vehicle model name"/>
<arg name="sensor_model" description="sensor model name"/>

<!-- Global Parameter Loader -->
<group scoped="false">
<include file="$(find-pkg-share global_parameter_loader)/launch/global_params.launch.py">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="vehicle_model" value="$(var vehicle_model)"/>
</include>
</group>

<!-- Robot State Publisher -->
<group>
<arg name="model_file" default="$(find-pkg-share tier4_vehicle_launch)/urdf/vehicle.xacro" description="path to the file of model settings (*.xacro)"/>
<arg name="config_dir" default="$(find-pkg-share racing_kart_sensor_kit_description)/config"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" exec="robot_state_publisher">
<param name="robot_description" value="$(command 'xacro $(var model_file) vehicle_model:=$(var vehicle_model) sensor_model:=$(var sensor_model) config_dir:=$(var config_dir)' 'warn')"/>
</node>
</group>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>
<push-ros-namespace namespace="control"/>
<node pkg="simple_pure_pursuit" exec="simple_pure_pursuit" name="simple_pure_pursuit_node" output="screen">
<param name="use_external_target_vel" value="true"/>
<param name="external_target_vel" value="8.0"/>
<param name="lookahead_gain" value="0.3"/>
<param name="lookahead_min_distance" value="4.0"/>
<param name="speed_proportional_gain" value="1.0"/>

<remap from="input/kinematics" to="/localization/kinematic_state"/>
<remap from="input/trajectory" to="/planning/scenario_planning/trajectory"/>
<remap from="output/control_cmd" to="/control/command/control_cmd"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>
<push-ros-namespace namespace="localization"/>
<include file="$(find-pkg-share gyro_odometer)/launch/gyro_odometer.launch.xml">
<arg name="input_vehicle_twist_with_covariance_topic" value="/sensing/vehicle_velocity_converter/twist_with_covariance"/>
<arg name="input_imu_topic" value="/sensing/imu/imu_data"/>
<arg name="output_twist_with_covariance_topic" value="/localization/twist_estimator/twist_with_covariance"/>
<arg name="output_twist_with_covariance_raw_topic" value="/localization/twist_estimator/twist_with_covariance_raw"/>
</include>

<node pkg="imu_gnss_poser" exec="imu_gnss_poser_node" name="imu_gnss_poser" output="screen"/>

<include file="$(find-pkg-share ekf_localizer)/launch/ekf_localizer.launch.xml">
<arg name="enable_yaw_bias_estimation" value="false"/>
<arg name="tf_rate" value="50.0"/>
<arg name="twist_smoothing_steps" value="1"/>
<arg name="input_initial_pose_name" value="/localization/initial_pose3d"/>
<arg name="input_pose_with_cov_name" value="/localization/imu_gnss_poser/pose_with_covariance"/>
<arg name="input_twist_with_cov_name" value="/localization/twist_estimator/twist_with_covariance"/>
<arg name="output_odom_name" value="kinematic_state"/>
<arg name="output_pose_name" value="pose"/>
<arg name="output_pose_with_covariance_name" value="/localization/pose_with_covariance"/>
<arg name="output_biased_pose_name" value="biased_pose"/>
<arg name="output_biased_pose_with_covariance_name" value="biased_pose_with_covariance"/>
<arg name="output_twist_name" value="twist"/>
<arg name="output_twist_with_covariance_name" value="twist_with_covariance"/>
<arg name="proc_stddev_vx_c" value="10.0"/>
<arg name="proc_stddev_wz_c" value="5.0"/>
</include>

<!-- twist2accel -->
<group>
<node pkg="twist2accel" exec="twist2accel" name="twist2accel" output="screen">
<param name="accel_lowpass_gain" value="0.9"/>
<param name="use_odom" value="true"/>
<remap from="input/odom" to="/localization/kinematic_state"/>
<remap from="input/twist" to="/localization/twist_estimator/twist_with_covariance"/>
<remap from="output/accel" to="/localization/acceleration"/>
</node>
</group>

</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>

<!-- Parameters -->
<arg name="map_path" />
<arg name="lanelet2_map_file" />

<group>
<push-ros-namespace namespace="map"/>

<!-- map_container -->
<node_container pkg="rclcpp_components" exec="component_container" name="map_container" namespace="">

<!-- map_loader::Lanelet2MapLoaderNode -->
<composable_node pkg="map_loader" plugin="Lanelet2MapLoaderNode" name="lanelet2_map_loader" namespace="">
<remap from="output/lanelet2_map" to="vector_map" />
<param name="lanelet2_map_path" value="$(var map_path)/$(var lanelet2_map_file)" />
<param from="$(find-pkg-share autoware_launch)/config/map/lanelet2_map_loader.param.yaml" />
<extra_arg name="use_intra_process_comms" value="false" />
</composable_node>

<!-- map_loader::Lanelet2MapVisualizationNode -->
<composable_node pkg="map_loader" plugin="Lanelet2MapVisualizationNode" name="lanelet2_map_visualization" namespace="">
<remap from="input/lanelet2_map" to="vector_map" />
<remap from="output/lanelet2_map_marker" to="vector_map_marker" />
<param name="lanelet2_map_path" value="$(var map_path)/$(var lanelet2_map_file)" />
<param from="$(find-pkg-share autoware_launch)/config/map/lanelet2_map_loader.param.yaml" />
<extra_arg name="use_intra_process_comms" value="false" />
</composable_node>

<!-- map_tf_generator::VectorMapTFGeneratorNode -->
<composable_node pkg="map_tf_generator" plugin="VectorMapTFGeneratorNode" name="vector_map_tf_generator" namespace="">
<param name="map_frame" value="map" />
<param name="viewer_frame" value="viewer" />
<extra_arg name="use_intra_process_comms" value="false" />
</composable_node>

</node_container>

</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>
<push-ros-namespace namespace="perception"/>
<node pkg="dummy_perception_publisher" exec="empty_objects_publisher" name="empty_objects_publisher" output="screen">
<remap from="~/output/objects" to="/perception/object_recognition/objects"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>
<push-ros-namespace namespace="planning"/>

<!-- mission_planning -->
<group>
<push-ros-namespace namespace="mission_planning"/>

<!-- mission_planner -->
<node pkg="mission_planner" exec="mission_planner" name="mission_planner" output="screen">
<remap from="input/modified_goal" to="/planning/scenario_planning/modified_goal"/>
<remap from="input/vector_map" to="/map/vector_map"/>
<!-- <remap from="/localization/kinematic_state" to="/awsim/ground_truth/localization/kinematic_state"/> -->
<remap from="debug/route_marker" to="/planning/mission_planning/route_marker"/>
<param from="$(find-pkg-share autoware_launch)/config/planning/mission_planning/mission_planner/mission_planner.param.yaml"/>
</node>

<!-- goal_pose_visualizer -->
<node pkg="mission_planner" exec="goal_pose_visualizer" name="goal_pose_visualizer" output="screen">
<remap from="input/route" to="/planning/mission_planning/route"/>
<remap from="output/goal_pose" to="/planning/mission_planning/echo_back_goal_pose"/>
</node>

</group> <!-- mission_planning -->

<!-- scenario_planning -->
<group>
<push-ros-namespace namespace="scenario_planning"/>

<!-- scenario_selector -->
<group>
<arg name="cmd" default="ros2 topic pub /planning/scenario_planning/scenario tier4_planning_msgs/msg/Scenario '{current_scenario: LaneDriving, activating_scenarios: [LaneDriving]}'"/>
<executable cmd="$(var cmd)" name="scenario_pub" shell="true"/>
</group> <!-- scenario_selector -->

<!-- operation_mode -->
<group>
<arg name="cmd" default="ros2 topic pub /system/operation_mode/state autoware_adapi_v1_msgs/msg/OperationModeState '{
mode: 1,
is_autoware_control_enabled: true,
is_in_transition: false,
is_stop_mode_available: true,
is_autonomous_mode_available: true,
is_local_mode_available: true,
is_remote_mode_available: true
}'"/>
<executable cmd="$(var cmd)" name="operation_mode_pub" shell="true"/>
</group> <!-- operation_mode -->

<!-- lane_driving -->
<group>
<push-ros-namespace namespace="lane_driving"/>

<!-- behavior_planning -->
<group>
<push-ros-namespace namespace="behavior_planning"/>

<!-- behavior_planning_container -->
<node_container pkg="rclcpp_components" exec="component_container" name="behavior_planning_container" namespace="">

<!-- behavior_path_planner::BehaviorPathPlannerNode -->
<composable_node pkg="behavior_path_planner" plugin="behavior_path_planner::BehaviorPathPlannerNode" name="behavior_path_planner" namespace="">
<remap from="~/input/route" to="/planning/mission_planning/route" />
<remap from="~/input/vector_map" to="/map/vector_map" />
<remap from="~/input/perception" to="/perception/object_recognition/objects" /> <!-- autoware_auto_perception_msgs/PredictedObjects -->
<remap from="~/input/occupancy_grid_map" to="/perception/occupancy_grid_map/map" />
<remap from="~/input/costmap" to="/planning/scenario_planning/parking/costmap_generator/occupancy_grid" />
<remap from="~/input/odometry" to="/localization/kinematic_state" />
<remap from="~/input/accel" to="/localization/acceleration" />
<remap from="~/input/scenario" to="/planning/scenario_planning/scenario" />
<remap from="~/output/path" to="path_with_lane_id" />
<remap from="~/output/turn_indicators_cmd" to="/planning/turn_indicators_cmd" />
<remap from="~/output/hazard_lights_cmd" to="/planning/hazard_lights_cmd" />
<remap from="~/output/modified_goal" to="/planning/scenario_planning/modified_goal" />
<param name="bt_tree_config_path" value="$(find-pkg-share aichallenge_submit_launch)/config/behavior_path_planner_tree.xml"/>
<param name="lane_change.enable_abort_lane_change" value="false"/>
<param name="lane_change.enable_collision_check_at_prepare_phase" value="false"/>
<param name="lane_change.use_predicted_path_outside_lanelet" value="false"/>
<param name="lane_change.use_all_predicted_path" value="false"/>
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/common/nearest_search.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_following/lane_following.param.yaml" />
<param from="$(find-pkg-share aichallenge_submit_launch)/config/behavior_path_planner.param.yaml" />
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml" />
<extra_arg name="use_intra_process_comms" value="false" />
</composable_node>

</node_container>
</group> <!-- behavior_planning -->
</group> <!-- lane_driving -->

<!-- Customizable -->
<node pkg="path_to_trajectory" exec="path_to_trajectory_node" name="path_to_trajectory" output="screen">
<remap from="input" to="/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id"/>
<remap from="output" to="/planning/scenario_planning/trajectory"/>
</node>

</group>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>

<push-ros-namespace namespace="sensing"/>

<!-- Vehicle Velocity Converter -->
<include file="$(find-pkg-share vehicle_velocity_converter)/launch/vehicle_velocity_converter.launch.xml">
<arg name="input_vehicle_velocity_topic" value="/vehicle/status/velocity_status"/>
<arg name="output_twist_with_covariance" value="/sensing/vehicle_velocity_converter/twist_with_covariance"/>
</include>

<!-- IMU Corrector -->
<group>
<push-ros-namespace namespace="imu"/>
<arg name="imu_corrector_param_file" default="$(find-pkg-share booars_launch)/config/sensing/imu_corrector.param.yaml"/>
<include file="$(find-pkg-share imu_corrector)/launch/imu_corrector.launch.xml">
<arg name="input_topic" value="imu_raw"/>
<arg name="output_topic" value="imu_data"/>
<arg name="param_file" value="$(var imu_corrector_param_file)"/>
</include>
</group>

</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<group>
<push-ros-namespace namespace="vehicle"/>
</group>
</launch>
Loading

0 comments on commit 0ea6e14

Please sign in to comment.