Add files
This commit is contained in:
parent
bcfaacd194
commit
a8c94b93eb
851 changed files with 74204 additions and 0 deletions
|
@ -0,0 +1,16 @@
|
|||
planning_dimension : "2D" # available dimension (2D,3D)
|
||||
planner_name : "CForest" # available planners (CForest, RRTstar)
|
||||
solving_time : 5.0 # available computation time to attempt to solve the query
|
||||
|
||||
#Configuration Space (C-Space) boundaries
|
||||
planning_bounds_x : [-15, 15]
|
||||
planning_bounds_y : [-15, 15]
|
||||
planning_bounds_z : [0, 15]
|
||||
|
||||
planning_depth_limit : 1
|
||||
|
||||
#Collision Mask
|
||||
collision_mask_x : 0.5
|
||||
collision_mask_y : 0.5
|
||||
collision_mask_z_2D : 0.2
|
||||
collision_mask_z_3D : 0.5
|
|
@ -0,0 +1,510 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 81
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /TF1/Tree1
|
||||
- /TF2/Frames1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 409
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.588679
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.03
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: odom
|
||||
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
|
||||
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_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
caster_front_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
cliff_sensor_front_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
cliff_sensor_left_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
cliff_sensor_right_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
gyro_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
plate_bottom_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
plate_middle_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
plate_top_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_0_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_1_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_2_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_3_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_4_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_bottom_5_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_kinect_0_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_kinect_1_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_middle_0_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_middle_1_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_middle_2_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_middle_3_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_top_0_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_top_1_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_top_2_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
pole_top_3_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
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: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 0.2972
|
||||
Min Value: 0.2972
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/LaserScan
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: AxisColor
|
||||
Decay Time: 0
|
||||
Enabled: false
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: LaserScan
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.01
|
||||
Style: Squares
|
||||
Topic: /scan
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: false
|
||||
- Alpha: 1
|
||||
Auto Size:
|
||||
Auto Size Factor: 1
|
||||
Value: true
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 3.286
|
||||
Min Value: 0.683
|
||||
Value: true
|
||||
Axis: X
|
||||
Channel Name: intensity
|
||||
Class: rviz/DepthCloud
|
||||
Color: 255; 255; 255
|
||||
Color Image Topic: ""
|
||||
Color Transformer: AxisColor
|
||||
Color Transport Hint: raw
|
||||
Decay Time: 0
|
||||
Depth Map Topic: /camera/depth/image_raw
|
||||
Depth Map Transport Hint: raw
|
||||
Enabled: false
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: DepthCloud
|
||||
Occlusion Compensation:
|
||||
Occlusion Time-Out: 30
|
||||
Value: false
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 5
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Style: Points
|
||||
Topic Filter: true
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: false
|
||||
- Alpha: 1
|
||||
Auto Size:
|
||||
Auto Size Factor: 1
|
||||
Value: true
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/DepthCloud
|
||||
Color: 255; 255; 255
|
||||
Color Image Topic: /camera/rgb/image_color
|
||||
Color Transformer: RGB8
|
||||
Color Transport Hint: raw
|
||||
Decay Time: 0
|
||||
Depth Map Topic: /camera/depth_registered/image_raw
|
||||
Depth Map Transport Hint: raw
|
||||
Enabled: false
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: Registered DepthCloud
|
||||
Occlusion Compensation:
|
||||
Occlusion Time-Out: 30
|
||||
Value: false
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 5
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Style: Points
|
||||
Topic Filter: true
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: false
|
||||
- Class: rviz/Image
|
||||
Enabled: false
|
||||
Image Topic: /camera/rgb/image_color
|
||||
Max Value: 1
|
||||
Median window: 5
|
||||
Min Value: 0
|
||||
Name: Image
|
||||
Normalize Range: true
|
||||
Queue Size: 2
|
||||
Transport Hint: raw
|
||||
Value: false
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 3.286
|
||||
Min Value: 0.681
|
||||
Value: true
|
||||
Axis: X
|
||||
Channel Name: intensity
|
||||
Class: rviz/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: AxisColor
|
||||
Decay Time: 0
|
||||
Enabled: false
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: PointCloud
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.01
|
||||
Style: Points
|
||||
Topic: /camera/depth/points
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: false
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 5.632
|
||||
Min Value: 0.65
|
||||
Value: true
|
||||
Axis: X
|
||||
Channel Name: intensity
|
||||
Class: rviz/PointCloud2
|
||||
Color: 255; 255; 255
|
||||
Color Transformer: RGB8
|
||||
Decay Time: 0
|
||||
Enabled: false
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: Registered PointCloud
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 3
|
||||
Size (m): 0.01
|
||||
Style: Points
|
||||
Topic: /camera/depth_registered/points
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: false
|
||||
- Class: rviz/InteractiveMarkers
|
||||
Enable Transparency: true
|
||||
Enabled: false
|
||||
Name: InteractiveMarkers
|
||||
Show Axes: false
|
||||
Show Descriptions: true
|
||||
Show Visual Aids: false
|
||||
Update Topic: /turtlebot_marker_server/update
|
||||
Value: false
|
||||
- Class: rviz/MarkerArray
|
||||
Enabled: true
|
||||
Marker Topic: /occupied_cells_vis_array
|
||||
Name: Octomap
|
||||
Namespaces:
|
||||
{}
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
- Class: rviz/Marker
|
||||
Enabled: true
|
||||
Marker Topic: /controller_turtlebot/solution_path
|
||||
Name: Planning Solution
|
||||
Namespaces:
|
||||
{}
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
- Class: rviz/TF
|
||||
Enabled: false
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: false
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: false
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: odom
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/SetInitialPose
|
||||
Topic: /initialpose
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 7.04007
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.06
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: -0.102786
|
||||
Y: -0.0889391
|
||||
Z: 0.112978
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.01
|
||||
Pitch: 0.584798
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 1.2554
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 625
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
Image:
|
||||
collapsed: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001950000022bfc0200000006fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000022b000000dd00fffffffb0000000a0049006d006100670065000000028d000000c60000001600ffffff000000010000010b00000294fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003300000294000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000003240000022b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1215
|
||||
X: 58
|
||||
Y: 24
|
|
@ -0,0 +1,17 @@
|
|||
<launch>
|
||||
<arg name="enable_octomap" value="true"/>
|
||||
<arg name="enable_goto_controller" value="false"/>
|
||||
|
||||
<group if="$(arg enable_octomap)">
|
||||
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server" args=" " cwd="node" output="screen">
|
||||
<param name="frame_id" value="/odom" />
|
||||
<remap from="/cloud_in" to="/camera/depth/points" /> <!-- simulator -->
|
||||
<!--remap from="/cloud_in" to="/camera/depth_registered/points" /--> <!-- real turtlebot -->
|
||||
</node>
|
||||
</group>
|
||||
|
||||
<group if="$(arg enable_goto_controller)">
|
||||
<node pkg="control_turtlebot" type="controller_turtlebot.py" name="controller_turtlebot" respawn="true" output="screen" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,35 @@
|
|||
<launch>
|
||||
<arg name="enable_octomap" value="true"/>
|
||||
<arg name="enable_controller" value="true"/>
|
||||
|
||||
<arg name="enable_plannerV2" value="true"/>
|
||||
|
||||
<group if="$(arg enable_octomap)">
|
||||
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server" args=" " cwd="node" output="screen">
|
||||
<param name="frame_id" value="/odom" />
|
||||
<!--remap from="/cloud_in" to="/pc_from_scan" /--> <!-- simulator -->
|
||||
<param name="resolution" value="0.05" />
|
||||
<param name="latch" value="True" />
|
||||
<param name="sensor_model/max_range" value="-1" /> <!-- -1 : unlimited -->
|
||||
<param name="sensor_model/hit" value="0.7" /> <!-- default value :0.7 -->
|
||||
<param name="sensor_model/miss" value="0.4" /> <!-- default value :0.4 -->
|
||||
|
||||
<param name="ground_filter/distance" value="0.04" /> <!-- default value :0.04 -->
|
||||
<param name="ground_filter/plane_distance" value="0.07" /> <!-- default value :0.07 -->
|
||||
<remap from="/cloud_in" to="/camera/depth/points" /> <!-- real turtlebot -->
|
||||
</node>
|
||||
</group>
|
||||
|
||||
<node pkg="control_turtlebot" type="laserscan_to_pointcloud" name="laserscan_to_pointcloud" respawn="true" output="screen" />
|
||||
|
||||
<group if="$(arg enable_controller)">
|
||||
<node pkg="control_turtlebot" type="controller_turtlebot.py" name="controller_turtlebot" respawn="true" output="screen" />
|
||||
</group>
|
||||
|
||||
<group if="$(arg enable_plannerV2)">
|
||||
<!-- OMPL planner -->
|
||||
<rosparam command="load" file="$(find control_turtlebot)/launch/config/planner_parameters.yaml" />
|
||||
<node pkg="control_turtlebot" type="Planning_Node" name="Planning_Node" output="screen" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,23 @@
|
|||
<launch>
|
||||
<arg name="enable_turtlebot_simulation" value="true"/>
|
||||
<arg name="enable_keyboard_teleoperation" value="true"/>
|
||||
<arg name="enable_rviz" value="true"/>
|
||||
|
||||
<group if="$(arg enable_turtlebot_simulation)">
|
||||
<include file="$(find turtlebot_gazebo)/launch/turtlebot_world.launch"/> <!-- other ROS distributions -->
|
||||
<!--include file="$(find turtlebot_gazebo)/launch/turtlebot_playground.launch"/--> <!-- ROS hydro -->
|
||||
|
||||
<group if="$(arg enable_rviz)">
|
||||
<include file="$(find control_turtlebot)/launch/view_robot.launch"/>
|
||||
</group>
|
||||
</group>
|
||||
<group unless="$(arg enable_turtlebot_simulation)">
|
||||
<include file="$(find turtlebot_bringup)/launch/minimal.launch"/>
|
||||
<include file="$(find turtlebot_bringup)/launch/3dsensor.launch"/>
|
||||
</group>
|
||||
|
||||
<group if="$(arg enable_keyboard_teleoperation)">
|
||||
<include file="$(find turtlebot_teleop)/launch/keyboard_teleop.launch">
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
|
@ -0,0 +1,7 @@
|
|||
<launch>
|
||||
<include file="$(find turtlebot_gazebo)/launch/turtlebot_world.launch">
|
||||
<arg name="world_file" value="$(find control_turtlebot)/worlds/willowgarage.world"/>
|
||||
</include>
|
||||
<include file="$(find turtlebot_teleop)/launch/keyboard_teleop.launch"/>
|
||||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find control_turtlebot)/launch/config/robot.rviz"/>
|
||||
</launch>
|
|
@ -0,0 +1,6 @@
|
|||
<launch>
|
||||
<!-- Offline planner ompl -->
|
||||
<rosparam command="load" file="$(find control_turtlebot)/launch/config/tests_blocks.yaml" />
|
||||
<node pkg="control_turtlebot" type="tutorial_offline_planner_R2" name="tutorial_offline_planner_R2" output="screen" />
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,8 @@
|
|||
<!--
|
||||
Used for visualising turtlebot in action.
|
||||
|
||||
It requires minimal.launch and optionally 3dsensor.launch to already be up and running.
|
||||
-->
|
||||
<launch>
|
||||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find control_turtlebot)/launch/config/robot.rviz" />
|
||||
</launch>
|
Loading…
Add table
Add a link
Reference in a new issue