Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

slam: added rtabmap example #484

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 38 additions & 0 deletions turtlebot3_slam/launch/turtlebot3_rtabmap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<launch>
<!-- Arguments -->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="configuration_basename" default="turtlebot3_lds_2d.lua"/>
<arg name="set_base_frame" default="base_footprint"/>
<arg name="set_odom_frame" default="odom"/>
<arg name="set_map_frame" default="map"/>

<!-- RTAB-Map -->
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="database_path" type="string" value="~/.ros/rtabmap.db"/>
<param name="frame_id" type="string" value="$(arg set_base_frame)"/>
<param name="map_frame_id" type="string" value="$(arg set_map_frame)"/>
<param if="$(eval model=='waffle')" name="subscribe_rgb" type="bool" value="true"/>
<param unless="$(eval model=='waffle')" name="subscribe_rgb" type="bool" value="false"/>
<param if="$(eval model=='waffle')" name="subscribe_depth" type="bool" value="true"/>
<param unless="$(eval model=='waffle')" name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_scan" type="bool" value="true"/>
<param name="approx_sync" type="bool" value="true"/>

<!-- inputs -->
<remap from="scan" to="/scan"/>
<remap from="odom" to="/odom"/>
<remap from="rgb/image" to="/camera/rgb/image_raw"/>
<remap from="depth/image" to="/camera/depth/image_raw"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>

<!-- output -->
<remap from="grid_map" to="/map"/>

<!-- RTAB-Map's parameters -->
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="GridGlobal/MinSize" type="string" value="20"/>
</node>
</group>
</launch>
2 changes: 1 addition & 1 deletion turtlebot3_slam/launch/turtlebot3_slam.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<!-- Arguments -->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="slam_methods" default="gmapping" doc="slam type [gmapping, cartographer, hector, karto, frontier_exploration]"/>
<arg name="slam_methods" default="gmapping" doc="slam type [gmapping, cartographer, hector, karto, frontier_exploration, rtabmap]"/>
<arg name="configuration_basename" default="turtlebot3_lds_2d.lua"/>
<arg name="open_rviz" default="true"/>

Expand Down
338 changes: 338 additions & 0 deletions turtlebot3_slam/rviz/turtlebot3_rtabmap.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,338 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 355
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_scan:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_depth_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_depth_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_rgb_frame:
Alpha: 1
Show Axes: false
Show Trail: false
camera_rgb_optical_frame:
Alpha: 1
Show Axes: false
Show Trail: false
caster_back_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
caster_back_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
wheel_left_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wheel_right_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_footprint:
Value: true
base_link:
Value: true
base_scan:
Value: true
camera_depth_frame:
Value: true
camera_depth_optical_frame:
Value: true
camera_link:
Value: true
camera_rgb_frame:
Value: true
camera_rgb_optical_frame:
Value: true
caster_back_left_link:
Value: true
caster_back_right_link:
Value: true
imu_link:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
{}
Update Interval: 0
Value: true
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map
Topic: /map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rtabmap_rviz_plugins/MapCloud
Cloud decimation: 4
Cloud from scan: false
Cloud max depth (m): 4
Cloud min depth (m): 0
Cloud voxel size (m): 0.009999999776482582
Color: 255; 255; 255
Color Transformer: ""
Download graph: false
Download map: false
Enabled: true
Filter ceiling (m): 0
Filter floor (m): 0
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: MapCloud
Node filtering angle (degrees): 30
Node filtering radius (m): 0
Position Transformer: ""
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /rtabmap/mapData
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 1
Class: rtabmap_rviz_plugins/MapGraph
Enabled: true
Global loop closure: 255; 0; 0
Local loop closure: 255; 255; 0
Merged neighbor: 255; 170; 0
Name: MapGraph
Neighbor: 0; 0; 255
Topic: /rtabmap/mapGraph
Unreliable: false
User: 255; 0; 0
Value: true
Virtual: 255; 0; 255
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/LaserScan
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0
Min Color: 0; 0; 0
Min Intensity: 0
Name: LaserScan
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /camera/rgb/image_raw
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 10
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.785398006439209
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Saved: ~
Window Geometry:
Camera:
collapsed: false
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001ee000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000231000000bc0000000000000000fb0000000c00430061006d0065007200610000000231000000bc0000001600000016fb0000000a0049006d0061006700650100000231000000bc0000001600ffffff000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 132
Y: 27