From cfe4f635493954402e46e24678b216be3c162418 Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Thu, 5 Mar 2020 11:16:10 +0100 Subject: [PATCH] Added some arguments for the following items: * move base params file name * common costmap params file name * local costmap params file name * global costmap params file name --- launch/include/gmapping.launch | 2 +- launch/include/move_base.launch | 42 +++---- launch/nav.launch | 137 +++++++++++------------ params/costmap/map/global_params.yaml | 2 +- params/costmap/no_map/global_params.yaml | 2 +- 5 files changed, 91 insertions(+), 94 deletions(-) diff --git a/launch/include/gmapping.launch b/launch/include/gmapping.launch index d367b72..7d65c4e 100644 --- a/launch/include/gmapping.launch +++ b/launch/include/gmapping.launch @@ -31,4 +31,4 @@ </group> -</launch> \ No newline at end of file +</launch> diff --git a/launch/include/move_base.launch b/launch/include/move_base.launch index d2a73c8..b75d411 100644 --- a/launch/include/move_base.launch +++ b/launch/include/move_base.launch @@ -2,18 +2,22 @@ <!-- --> <launch> - <arg name="ns" default="robot"/> - <arg name="path" default="$(find iri_rosnav)/params"/> - <arg name="use_map" default="true"/> - <arg name="map_topic" default="/$(arg ns)/map)"/> - <arg name="odom_topic" default="/$(arg ns)/odom"/> - <arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/> - <arg name="local_planner" default="dwa"/> - <arg name="global_planner" default="global_planner"/> - <arg name="costmap_path" value="map" if="$(arg use_map)"/> - <arg name="costmap_path" value="no_map" unless="$(arg use_map)"/> - <arg name="output" default="screen" /> - <arg name="launch_prefix" default="" /> + <arg name="ns" default="robot"/> + <arg name="path" default="$(find iri_rosnav)/params"/> + <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="use_map" default="true"/> + <arg name="map_topic" default="/$(arg ns)/map)"/> + <arg name="odom_topic" default="/$(arg ns)/odom"/> + <arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/> + <arg name="local_planner" default="dwa"/> + <arg name="global_planner" default="global_planner"/> + <arg name="costmap_path" value="map" if="$(arg use_map)"/> + <arg name="costmap_path" value="no_map" unless="$(arg use_map)"/> + <arg name="output" default="screen" /> + <arg name="launch_prefix" default="" /> <group ns="$(arg ns)"> @@ -26,15 +30,15 @@ <remap from="cmd_vel" to="$(arg cmd_vel_topic)" /> <remap from="odom" to="$(arg odom_topic)" /> - <rosparam file="$(arg path)/move_base_params.yaml" command="load" /> - <rosparam file="$(arg path)/local_planner/$(arg local_planner)_params.yaml" command="load" /> - <rosparam file="$(arg path)/global_planner/$(arg global_planner)_params.yaml" command="load" /> + <rosparam file="$(arg path)/$(arg move_base_params)" command="load" /> + <rosparam file="$(arg path)/local_planner/$(arg local_planner)_params.yaml" command="load" /> + <rosparam file="$(arg path)/global_planner/$(arg global_planner)_params.yaml" command="load" /> - <rosparam file="$(arg path)/costmap/common_params.yaml" command="load" ns="local_costmap" /> - <rosparam file="$(arg path)/costmap/local_params.yaml" command="load" ns="local_costmap"/> + <rosparam file="$(arg path)/costmap/$(arg costmap_common_params)" command="load" ns="local_costmap" /> + <rosparam file="$(arg path)/costmap/$(arg costmap_local_params)" command="load" ns="local_costmap"/> - <rosparam file="$(arg path)/costmap/common_params.yaml" command="load" ns="global_costmap" /> - <rosparam file="$(arg path)/costmap/$(arg costmap_path)/global_params.yaml" command="load" ns="global_costmap"/> + <rosparam file="$(arg path)/costmap/$(arg costmap_common_params)" command="load" ns="global_costmap" /> + <rosparam file="$(arg path)/costmap/$(arg costmap_path)/$(arg costmap_global_params)" command="load" ns="global_costmap"/> </node> diff --git a/launch/nav.launch b/launch/nav.launch index 918e07f..a570c34 100644 --- a/launch/nav.launch +++ b/launch/nav.launch @@ -1,39 +1,38 @@ <?xml version="1.0"?> <!-- --> <launch> - <arg name="ns" default="robot"/> - <arg name="pkg" default="iri_rosnav"/> - <arg name="path" default="$(eval find(arg('pkg')))"/> - <arg name="param_subpath" default="params"/> - <arg name="map_frame_id" default="map"/> - <arg name="odom_frame_id" default="$(arg ns)/odom"/> - <arg name="base_frame_id" default="$(arg ns)/base_footprint"/> - <arg name="map_topic" default="/$(arg ns)/map"/> - <arg name="map_service" default="/$(arg ns)/static_map"/> - <arg name="odom_topic" default="/$(arg ns)/odom"/> - <arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/> - <arg name="scan_topic" default="/$(arg ns)/sensors/scan"/> - <arg name="use_map" default="true"/> - <arg name="use_map_server" default="true"/> - <arg name="map_name" default="willow"/> - <arg name="use_amcl" default="true"/> - <arg name="amcl_config" default="$(arg path)/$(arg param_subpath)/amcl.yaml"/> - <arg name="initial_x" default="0.0"/> - <arg name="initial_y" default="0.0"/> - <arg name="initial_yaw" default="0.0"/> - <arg name="use_fake_loc" default="false"/> - <arg name="use_gmapping" default="false"/> - <arg name="gmapping_scan_topic" default="/$(arg ns)/front_hokuyo_scan"/> - <arg name="gmapping_config" default="$(arg path)/$(arg param_subpath)/gmapping.yaml"/> - <arg name="resolution" default="0.1"/> - <arg name="use_cmd_vel_mux" default="false"/> - <arg name="nodelet_manager_name" default="nodelet_manager"/> - <arg name="cmd_vel_mux_config" default="$(arg path)/$(arg param_subpath)/mux.yaml"/> - <arg name="use_move_base" default="true"/> - <arg name="local_planner" default="dwa"/> - <arg name="global_planner" default="global_planner"/> - <arg name="output" default="screen" /> - <arg name="launch_prefix" default="" /> + <arg name="ns" default="robot"/> + <arg name="path" default="$(find iri_rosnav)/params"/> + <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="map_frame_id" default="map"/> + <arg name="odom_frame_id" default="$(arg ns)/odom"/> + <arg name="base_frame_id" default="$(arg ns)/base_footprint"/> + <arg name="map_topic" default="/$(arg ns)/map"/> + <arg name="map_service" default="/$(arg ns)/static_map"/> + <arg name="odom_topic" default="/$(arg ns)/odom"/> + <arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/> + <arg name="scan_topic" default="/$(arg ns)/sensors/scan"/> + <arg name="use_map" default="true"/> + <arg name="use_map_server" default="true"/> + <arg name="map_name" default="willow"/> + <arg name="use_amcl" default="true"/> + <arg name="amcl_config" default="$(arg path)/amcl.yaml"/> + <arg name="initial_x" default="0.0"/> + <arg name="initial_y" default="0.0"/> + <arg name="initial_yaw" default="0.0"/> + <arg name="use_fake_loc" default="false"/> + <arg name="use_gmapping" default="false"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/front_hokuyo_scan"/> + <arg name="gmapping_config" default="$(arg path)/gmapping.yaml"/> + <arg name="resolution" default="0.1"/> + <arg name="use_move_base" default="true"/> + <arg name="local_planner" default="dwa"/> + <arg name="global_planner" default="global_planner"/> + <arg name="output" default="screen" /> + <arg name="launch_prefix" default="" /> <group if="$(arg use_map)"> <group if="$(arg use_map_server)"> @@ -67,16 +66,16 @@ <group if="$(arg use_gmapping)"> <include file="$(find iri_rosnav)/launch/include/gmapping.launch"> - <arg name="ns" value="$(arg ns)"/> - <arg name="resolution" value="$(arg resolution)"/> - <arg name="config" value="$(arg gmapping_config)"/> - <arg name="map_frame_id" value="$(arg map_frame_id)"/> - <arg name="odom_frame_id" value="$(arg odom_frame_id)"/> - <arg name="base_frame_id" value="$(arg base_frame_id)"/> + <arg name="ns" value="$(arg ns)"/> + <arg name="resolution" value="$(arg resolution)"/> + <arg name="config" value="$(arg gmapping_config)"/> + <arg name="map_frame_id" value="$(arg map_frame_id)"/> + <arg name="odom_frame_id" value="$(arg odom_frame_id)"/> + <arg name="base_frame_id" value="$(arg base_frame_id)"/> <arg name="gmapping_scan_topic" value="$(arg gmapping_scan_topic)"/> - <arg name="map_topic" value="$(arg map_topic)"/> - <arg name="output" value="$(arg output)" /> - <arg name="launch_prefix" value="$(arg launch_prefix)" /> + <arg name="map_topic" value="$(arg map_topic)"/> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> </group> </group> @@ -92,42 +91,36 @@ <group if="$(arg use_fake_loc)"> <include file="$(find iri_rosnav)/launch/include/fake_loc.launch"> - <arg name="ns" value="$(arg ns)"/> - <arg name="map_frame_id" value="$(arg map_frame_id)"/> - <arg name="odom_frame_id" value="$(arg odom_frame_id)"/> - <arg name="base_frame_id" value="$(arg base_frame_id)"/> - <arg name="initial_x" value="$(arg initial_x)"/> - <arg name="initial_y" value="$(arg initial_y)"/> - <arg name="initial_yaw" value="$(arg initial_yaw)"/> - <arg name="odom_topic" value="$(arg odom_topic)"/> + <arg name="ns" value="$(arg ns)"/> + <arg name="map_frame_id" value="$(arg map_frame_id)"/> + <arg name="odom_frame_id" value="$(arg odom_frame_id)"/> + <arg name="base_frame_id" value="$(arg base_frame_id)"/> + <arg name="initial_x" value="$(arg initial_x)"/> + <arg name="initial_y" value="$(arg initial_y)"/> + <arg name="initial_yaw" value="$(arg initial_yaw)"/> + <arg name="odom_topic" value="$(arg odom_topic)"/> <arg name="ground_truth_topic" value="$(arg odom_topic)"/> - <arg name="output" value="$(arg output)" /> - <arg name="launch_prefix" value="$(arg launch_prefix)" /> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> </group> - <group if="$(arg use_cmd_vel_mux)"> - <include file="$(find iri_rosnav)/launch/include/cmd_vel_mux.launch"> - <arg name="ns" value="$(arg ns)"/> - <arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)"/> - <arg name="config" value="$(arg cmd_vel_mux_config)"/> - <arg name="output" value="$(arg output)" /> - <arg name="launch_prefix" value="$(arg launch_prefix)" /> - </include> - </group> - <group if="$(arg use_move_base)"> <include file="$(find iri_rosnav)/launch/include/move_base.launch"> - <arg name="ns" value="$(arg ns)"/> - <arg name="path" value="$(arg path)/$(arg param_subpath)"/> - <arg name="use_map" value="$(arg use_map_server)"/> - <arg name="map_topic" value="$(arg map_topic)"/> - <arg name="odom_topic" value="$(arg odom_topic)"/> - <arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)"/> - <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)" /> + <arg name="ns" value="$(arg ns)"/> + <arg name="path" value="$(arg path)"/> + <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="use_map" value="$(arg use_map_server)"/> + <arg name="map_topic" value="$(arg map_topic)"/> + <arg name="odom_topic" value="$(arg odom_topic)"/> + <arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)"/> + <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> </group> diff --git a/params/costmap/map/global_params.yaml b/params/costmap/map/global_params.yaml index aef60d4..5c61d57 100644 --- a/params/costmap/map/global_params.yaml +++ b/params/costmap/map/global_params.yaml @@ -18,4 +18,4 @@ static_layer: use_maximum: false lethal_cost_threshold: 100 track_unknown_space: true - trinary_costmap: true \ No newline at end of file + trinary_costmap: true diff --git a/params/costmap/no_map/global_params.yaml b/params/costmap/no_map/global_params.yaml index 48192a0..9d5b1dc 100644 --- a/params/costmap/no_map/global_params.yaml +++ b/params/costmap/no_map/global_params.yaml @@ -12,4 +12,4 @@ origin_y: 0.0 plugins: - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} - - {name: inflation_layer, type: "costmap_2d::InflationLayer"} \ No newline at end of file + - {name: inflation_layer, type: "costmap_2d::InflationLayer"} -- GitLab