diff --git a/launch/nav_map.launch b/launch/nav_map.launch index 726b418973b0690635b33f0f1096f2c3fb6a9bbe..5353c3d71d87eeb23a78d115b41770c9b90e4b7a 100644 --- a/launch/nav_map.launch +++ b/launch/nav_map.launch @@ -14,7 +14,7 @@ <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/scans"/> + <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" /> @@ -25,7 +25,7 @@ <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)/sensors/front_laser_scan"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/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="true"/> @@ -69,20 +69,14 @@ <arg name="output" value="$(arg output)" /> <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> - - <group ns="$(arg ns)"> - - <node name="front_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/front_laser_scan $(arg scan_topic)"/> - - <node name="rear_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/rear_laser_scan $(arg scan_topic)"/> - - </group> + + <include file="$(find iri_rosnav)/launch/include/pointcloud_to_laserscan.launch"> + <arg name="ns" value="$(arg ns)"/> + <arg name="scan_topic" value="$(arg scan_topic)"/> + <arg name="cloud_topic" value="/$(arg ns)/sensors/rslidar_points"/> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> + </include> <node name="rviz" pkg="rviz" @@ -91,4 +85,4 @@ args="-d $(arg path)/rviz/$(arg ns).rviz"> </node> -</launch> \ No newline at end of file +</launch> diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch index e84e1e63aa47a077b3925d08945658654db604be..5857d9b388a782eb1d3487f6120770a1c3e614a5 100644 --- a/launch/nav_mapping.launch +++ b/launch/nav_mapping.launch @@ -25,7 +25,7 @@ <arg name="initial_yaw" default="0.0"/> <arg name="use_fake_loc" default="false"/> <arg name="use_gmapping" default="true"/> - <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/front_laser_scan"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/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="true"/> @@ -69,21 +69,15 @@ <arg name="output" value="$(arg output)" /> <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> - - <group ns="$(arg ns)"> - - <node name="front_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/front_laser_scan $(arg scan_topic)"/> - - <node name="rear_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/rear_laser_scan $(arg scan_topic)"/> - - </group> - + + <include file="$(find iri_rosnav)/launch/include/pointcloud_to_laserscan.launch"> + <arg name="ns" value="$(arg ns)"/> + <arg name="scan_topic" value="$(arg scan_topic)"/> + <arg name="cloud_topic" value="/$(arg ns)/sensors/rslidar_points"/> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> + </include> + <node name="rviz" pkg="rviz" type="rviz" @@ -91,4 +85,4 @@ args="-d $(arg path)/rviz/$(arg ns).rviz"> </node> -</launch> \ No newline at end of file +</launch> diff --git a/launch/nav_nomap.launch b/launch/nav_nomap.launch index afb00397661dfdb941c506ab76aecb3225c0a3f7..cc75c1efdb2f13542ef89474895bbb81a89904a8 100644 --- a/launch/nav_nomap.launch +++ b/launch/nav_nomap.launch @@ -25,7 +25,7 @@ <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)/sensors/front_laser_scan"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/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="true"/> @@ -70,19 +70,13 @@ <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> - <group ns="$(arg ns)"> - - <node name="front_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/front_laser_scan $(arg scan_topic)"/> - - <node name="rear_laser_relay" - pkg="topic_tools" - type="relay" - args="sensors/rear_laser_scan $(arg scan_topic)"/> - - </group> + <include file="$(find iri_rosnav)/launch/include/pointcloud_to_laserscan.launch"> + <arg name="ns" value="$(arg ns)"/> + <arg name="scan_topic" value="$(arg scan_topic)"/> + <arg name="cloud_topic" value="/$(arg ns)/sensors/rslidar_points"/> + <arg name="output" value="$(arg output)" /> + <arg name="launch_prefix" value="$(arg launch_prefix)" /> + </include> <node name="rviz" pkg="rviz" @@ -91,4 +85,4 @@ args="-d $(arg path)/rviz/$(arg ns).rviz"> </node> -</launch> \ No newline at end of file +</launch> diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml index 27950f0ed32d5196cbfbf86653c823e91a572dfd..69db1eb705d94017802732bf286f940a240acf5a 100644 --- a/params/costmap/common_params.yaml +++ b/params/costmap/common_params.yaml @@ -27,7 +27,7 @@ obstacle_layer: velodyne: { sensor_frame: /helena/robosense, data_type: PointCloud2, - topic: /ana/sensors/rslidar_points, + topic: /helena/sensors/rslidar_points, observation_persistence: 0.0, marking: true, clearing: true, @@ -56,4 +56,4 @@ inflation_layer: enabled: true inflate_unknown: false cost_scaling_factor: 2.0 - inflation_radius: 1.0 \ No newline at end of file + inflation_radius: 1.0