diff --git a/launch/nav_map.launch b/launch/nav_map.launch index a9d3e2588b77da6a6a66bda9fb24cde73542940c..726b418973b0690635b33f0f1096f2c3fb6a9bbe 100644 --- a/launch/nav_map.launch +++ b/launch/nav_map.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/scans"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/front_laser_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"/> @@ -75,12 +75,12 @@ <node name="front_laser_relay" pkg="topic_tools" type="relay" - args="sensors/front_scan $(arg scan_topic)"/> + args="sensors/front_laser_scan $(arg scan_topic)"/> <node name="rear_laser_relay" pkg="topic_tools" type="relay" - args="sensors/rear_scan $(arg scan_topic)"/> + args="sensors/rear_laser_scan $(arg scan_topic)"/> </group> diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch index 5e79c320c4070e2698dec1ae8ecf0548c562da9b..e84e1e63aa47a077b3925d08945658654db604be 100644 --- a/launch/nav_mapping.launch +++ b/launch/nav_mapping.launch @@ -6,7 +6,7 @@ <arg name="ns" default="helena"/> <arg name="pkg" default="iri_helena_rosnav"/> <arg name="path" default="$(eval find(arg('pkg')))"/> - <arg name="param_subpath" default="params"/> + <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"/> @@ -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_scan"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/front_laser_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"/> @@ -75,12 +75,12 @@ <node name="front_laser_relay" pkg="topic_tools" type="relay" - args="sensors/front_scan $(arg scan_topic)"/> + args="sensors/front_laser_scan $(arg scan_topic)"/> <node name="rear_laser_relay" pkg="topic_tools" type="relay" - args="sensors/rear_scan $(arg scan_topic)"/> + args="sensors/rear_laser_scan $(arg scan_topic)"/> </group> diff --git a/launch/nav_nomap.launch b/launch/nav_nomap.launch index fd698059ef135c56906793a8132071a7c7ac625a..afb00397661dfdb941c506ab76aecb3225c0a3f7 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/scan"/> + <arg name="gmapping_scan_topic" default="/$(arg ns)/sensors/front_laser_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"/> @@ -75,12 +75,12 @@ <node name="front_laser_relay" pkg="topic_tools" type="relay" - args="sensors/front_scan $(arg scan_topic)"/> + args="sensors/front_laser_scan $(arg scan_topic)"/> <node name="rear_laser_relay" pkg="topic_tools" type="relay" - args="sensors/rear_scan $(arg scan_topic)"/> + args="sensors/rear_laser_scan $(arg scan_topic)"/> </group> diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml index 73c725c3d20fc075dcfbde12c5c24ea115f45b76..4356198dddd808a931943880092c7c69bc9623e6 100644 --- a/params/costmap/common_params.yaml +++ b/params/costmap/common_params.yaml @@ -26,7 +26,7 @@ obstacle_layer: front_laser: { sensor_frame: /helena/front_hokuyo_scan_frame, data_type: LaserScan, - topic: /helena/sensors/front_scan, + topic: /helena/sensors/front_laser_scan, observation_persistence: 0.0, marking: true, clearing: true, @@ -40,7 +40,7 @@ obstacle_layer: rear_laser: { sensor_frame: /helena/rear_hokuyo_scan_frame, data_type: LaserScan, - topic: /helena/sensors/rear_scan, + topic: /helena/sensors/rear_laser_scan, observation_persistence: 0.0, marking: true, clearing: true, diff --git a/rviz/helena.rviz b/rviz/helena.rviz index f1916e84464f81a35fdf5542d430e001c6f55c46..f1b337e7595500fdd233b143581bd40ab251cc21 100644 --- a/rviz/helena.rviz +++ b/rviz/helena.rviz @@ -334,7 +334,7 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.00999999978 Style: Points - Topic: /helena/sensors/front_scan + Topic: /helena/sensors/front_laser_scan Unreliable: false Use Fixed Frame: true Use rainbow: true @@ -364,7 +364,7 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.00999999978 Style: Points - Topic: /helena/sensors/rear_scan + Topic: /helena/sensors/rear_laser_scan Unreliable: false Use Fixed Frame: true Use rainbow: true @@ -680,7 +680,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 43.6349297 + Distance: 12.624259 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 @@ -695,10 +695,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 1.45539761 + Pitch: 1.4603982 Target Frame: <Fixed Frame> Value: Orbit (rviz) - Yaw: 1.61539745 + Yaw: 1.55539751 Saved: ~ Window Geometry: Displays: