Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_turtlebot_launch
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package Registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alejandro Lopez Gestoso
iri_turtlebot_launch
Commits
852ab483
Commit
852ab483
authored
3 years ago
by
Fernando Herrero
Browse files
Options
Downloads
Patches
Plain Diff
Add mapping launch and update mapping yaml parameters
parent
6baae790
No related branches found
No related tags found
1 merge request
!1
Update
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
launch/nav_mapping.launch
+56
-0
56 additions, 0 deletions
launch/nav_mapping.launch
params/gmapping.yaml
+18
-10
18 additions, 10 deletions
params/gmapping.yaml
with
74 additions
and
10 deletions
launch/nav_mapping.launch
0 → 100644
+
56
−
0
View file @
852ab483
<?xml version="1.0"?>
<!-- -->
<launch>
<arg
name=
"name"
default=
"turtlebot"
/>
<arg
name=
"path"
default=
"$(find iri_turtlebot_launch)/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=
"resolution"
default=
"0.1"
/>
<arg
name=
"local_planner"
default=
"dwa"
/>
<arg
name=
"global_planner"
default=
"global_planner"
/>
<arg
name=
"rviz"
default=
"true"
/>
<arg
name=
"rviz_file"
default=
"$(find iri_turtlebot_launch)/rviz/nav.rviz"
/>
<arg
name=
"output"
default=
"screen"
/>
<arg
name=
"launch_prefix"
default=
""
/>
<include
file=
"$(find iri_rosnav)/launch/nav.launch"
>
<arg
name=
"ns"
value=
"$(arg name)"
/>
<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=
"map_frame_id"
value=
"map"
/>
<arg
name=
"odom_frame_id"
value=
"odom"
/>
<arg
name=
"base_frame_id"
value=
"base_footprint"
/>
<arg
name=
"map_topic"
value=
"/$(arg name)/map"
/>
<arg
name=
"map_service"
value=
"/$(arg name)/static_map"
/>
<arg
name=
"odom_topic"
value=
"/odom"
/>
<arg
name=
"cmd_vel_topic"
value=
"/cmd_vel_mux/input/navi"
/>
<arg
name=
"scan_topic"
value=
"/scan"
/>
<arg
name=
"use_map"
value=
"true"
/>
<arg
name=
"use_map_server"
value=
"false"
/>
<arg
name=
"map_name"
value=
"empty"
/>
<arg
name=
"use_amcl"
value=
"false"
/>
<arg
name=
"use_fake_loc"
value=
"false"
/>
<arg
name=
"use_gmapping"
value=
"true"
/>
<arg
name=
"gmapping_scan_topic"
value=
"/scan"
/>
<arg
name=
"gmapping_config"
value=
"$(find iri_turtlebot_launch)/params/gmapping.yaml"
/>
<arg
name=
"resolution"
value=
"$(arg resolution)"
/>
<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>
<node
name=
"rviz"
pkg=
"rviz"
type=
"rviz"
if=
"$(arg rviz)"
args=
"-d $(arg rviz_file)"
>
</node>
</launch>
This diff is collapsed.
Click to expand it.
params/gmapping.yaml
+
18
−
10
View file @
852ab483
map_update_interval
:
5.0
maxUrange
:
29.0
#name: value #default_value
throttle_scans
:
1
#base_frame: base_link
#map_frame: map
#odom_frame: odom
map_update_interval
:
1.0
#5.0
maxUrange
:
7.8
#80.0
sigma
:
0.05
kernelSize
:
1
lstep
:
0.05
...
...
@@ -8,23 +14,25 @@ iterations: 5
lsigma
:
0.075
ogain
:
3.0
lskip
:
0
minimumScore
:
0.0
#0.0
srr
:
0.1
srt
:
0.2
str
:
0.1
stt
:
0.2
linearUpdate
:
0.
5
angularUpdate
:
0.5
temporalUpdate
:
1
0
.0
linearUpdate
:
0.
1
#1.0
angularUpdate
:
0.05
#
0.5
temporalUpdate
:
1
.0
#-1
.0
resampleThreshold
:
0.5
particles
:
80
particles
:
80
#30
xmin
:
-5.0
ymin
:
-5.0
xmax
:
5.0
ymax
:
5.0
delta
:
0.1
delta
:
0.05
#0.05
llsamplerange
:
0.01
llsamplestep
:
0.01
lasamplerange
:
0.005
lasamplestep
:
0.005
\ No newline at end of file
lasamplestep
:
0.005
transform_publish_period
:
0.05
occ_thresh
:
0.25
maxRange
:
8.5
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment