diff --git a/launch/nav_opendrive_map.launch b/launch/nav_opendrive_map.launch new file mode 100644 index 0000000000000000000000000000000000000000..6eff412df6447232177f8245d5f24d53085b8979 --- /dev/null +++ b/launch/nav_opendrive_map.launch @@ -0,0 +1,66 @@ +<?xml version="1.0"?> +<!-- --> +<launch> + + <arg name="move_base_params" default="move_base_params.yaml"/> + <arg name="costmap_common_params" default="common_params.yaml"/> + <arg name="costmap_local_params" default="local_params.yaml"/> + <arg name="costmap_global_params" default="global_params.yaml"/> + <arg name="local_planner" default="ackermann"/> + <arg name="global_planner" default="iri_opendrive"/> + <arg name="odom_topic" default="/model_car/odom"/> + <arg name="map_name" default="empty"/> + <arg name="output" default="screen" /> + <arg name="launch_prefix" default="" /> + <arg name="road_name" default="adc_road_big"/> + <arg name="road_size" default="9.9101"/> + <arg name="road_path" default="$(env HOME)/Documents/"/> + <arg name="road_x" default="3.5"/> + <arg name="road_y" default="3.99997"/> + <arg name="road_yaw" default="1.5707"/> + <arg name="road_parent_frame_id" default="map"/> + + <include file="$(find iri_rosnav)/launch/nav.launch"> + <arg name="ns" value="model_car"/> + <arg name="path" value="$(find model_car_rosnav)/params"/> + <arg name="move_base_params" value="$(arg move_base_params)"/> + <arg name="costmap_common_params" value="$(arg costmap_common_params)"/> + <arg name="costmap_local_params" value="$(arg costmap_local_params)"/> + <arg name="costmap_global_params" value="$(arg costmap_global_params)"/> + <arg name="map_frame_id" value="map"/> + <arg name="odom_frame_id" value="model_car/odom"/> + <arg name="base_frame_id" value="model_car/base_footprint"/> + <arg name="map_topic" value="/model_car/map"/> + <arg name="map_service" value="/model_car/static_map"/> + <arg name="odom_topic" value="$(arg odom_topic)"/> + <arg name="cmd_vel_topic" value="/model_car/cmd_vel"/> + <arg name="scan_topic" value="/model_car/sensors/scan"/> + <arg name="use_map" value="true"/> + <arg name="use_map_server" value="true"/> + <arg name="map_name" value="$(arg map_name)"/> + <arg name="use_amcl" value="true"/> + <arg name="amcl_config" value="$(find model_car_rosnav)/params/amcl.yaml"/> + <arg name="use_fake_loc" value="false"/> + <arg name="initial_x" value="0.0"/> + <arg name="initial_y" value="0.0"/> + <arg name="initial_yaw" value="0.0"/> + <arg name="use_gmapping" value="false"/> + <arg name="local_planner" value="$(arg local_planner)"/> + <arg name="global_planner" value="$(arg global_planner)"/> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> + </include> + + <param name="/model_car/move_base/OpendriveGlobalPlanner/opendrive_file" value="$(find model_car_rosnav)/adc_road.xodr" /> + + <include file="$(find road_description)/launch/spawn_road.launch"> + <arg name="road_name" value="$(arg road_name)"/> + <arg name="road_size" value="$(arg road_size)"/> + <arg name="road_path" value="$(arg road_path)"/> + <arg name="x" value="$(arg road_x)"/> + <arg name="y" value="$(arg road_y)"/> + <arg name="yaw" value="$(arg road_yaw)"/> + <arg name="parent" value="$(arg road_parent_frame_id)"/> + </include> + +</launch>