mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-03 21:54:12 +05:30
added full navigation stack with map of playground world.
This commit is contained in:
parent
5d132dd630
commit
7bde1497ec
@ -6,4 +6,4 @@ inflation_radius: 0.5
|
||||
|
||||
observation_sources: laser_scan_kinect
|
||||
|
||||
laser_scan_kinect: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
|
||||
laser_scan_kinect: {sensor_frame: qt_pi/laser, data_type: LaserScan, topic: /qt_pi/scan, marking: true, clearing: true}
|
||||
|
@ -4,3 +4,5 @@ global_costmap:
|
||||
update_frequency: 5.0
|
||||
static_map: false
|
||||
rolling_window: true
|
||||
width: 100
|
||||
height: 100
|
||||
|
@ -1,10 +1,9 @@
|
||||
<launch>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find qt_pi_gazebo_sim)/worlds/playground.world"/>
|
||||
<arg name="world_name" value="$(find qt_pi_gazebo_sim)/worlds/qt_pi_laser.world"/>
|
||||
</include>
|
||||
<!-- <include file="$(find qt_pi_gazebo_sim)/launch/depth_to_laser.launch"/> -->
|
||||
<include file="$(find qt_pi_gazebo_sim)/launch/static_tf.launch"/>
|
||||
<include file="$(find qt_pi_gazebo_sim)/launch/depth_to_laser.launch"/>
|
||||
<include file="$(find qt_pi_gazebo_sim)/launch/gmapping.launch"/>
|
||||
|
||||
</launch>
|
||||
</launch>
|
@ -1,8 +1,10 @@
|
||||
<launch>
|
||||
<remap from="scan" to="qt_pi/scan"/>
|
||||
<node name="gmapping" pkg="gmapping" type="slam_gmapping">
|
||||
<param name="base_frame" value="qt_pi/base_link" type="string"/>
|
||||
<param name="odom_frame" value="qt_pi/odom" type="string"/>
|
||||
<param name="maxUrange" value="90"/>
|
||||
<param name="maxRange" value="100"/>
|
||||
|
||||
<param name="maxUrange" value="9"/>
|
||||
<param name="maxRange" value="10"/>
|
||||
</node>
|
||||
</launch>
|
@ -1,9 +1,17 @@
|
||||
<launch>
|
||||
<master auto="start"/>
|
||||
<remap from="scan" to="qt_pi/scan"/>
|
||||
<remap from="cmd_vel" to="qt_pi/cmd_vel"/>
|
||||
<remap from="odom" to="qt_pi/odom"/>
|
||||
<node name="map_server" pkg="map_server" type="map_server" args="$(find qt_pi_gazebo_sim)/map/playground.yaml"/>
|
||||
|
||||
<node name="map_server" pkg="map_server" type="map_server" args="$(find qt_pi_gazebo_sim)/map/Untitled.pgm 0.05"/>
|
||||
<node name="amcl" pkg="amcl" type="amcl">
|
||||
|
||||
<include file="$(find amcl)/examples/amcl_diff.launch"/>
|
||||
<param name="base_frame_id" value="qt_pi/base_link" type="string"/>
|
||||
<param name="odom_frame_id" value="qt_pi/odom" type="string"/>
|
||||
<param name="odom_model_type" value="diff" type="string"/>
|
||||
|
||||
</node>
|
||||
|
||||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
|
||||
<rosparam file="$(find qt_pi_gazebo_sim)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
|
||||
|
@ -1,7 +1,9 @@
|
||||
<launch>
|
||||
|
||||
<remap from="odom" to="qt_pi/odom"/>
|
||||
<remap from="scan" to="qt_pi/scan"/>
|
||||
<remap from="cmd_vel" to="qt_pi/cmd_vel"/>
|
||||
<remap from="odom" to="qt_pi/odom"/>
|
||||
<include file="$(find qt_pi_gazebo_sim)/launch/gmapping.launch"/>
|
||||
|
||||
<node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
|
||||
<param name="footprint_padding" value="0.01"/>
|
||||
<param name="controller_frequency" value="10.0"/>
|
@ -1,3 +1,3 @@
|
||||
<launch>
|
||||
<node pkg="tf" type="static_transform_publisher" name="camera_depth" args="0.2 0 0.2 0 0 0 1 qt_pi/base_link camera_depth_frame 33"/>
|
||||
<node pkg="tf" type="static_transform_publisher" name="laser_frame" args="0.2 0 0.2 0 0 0 1 qt_pi/base_link qt_pi/laser 33"/>
|
||||
</launch>
|
8
gazebo_sim/map/frames.gv
Normal file
8
gazebo_sim/map/frames.gv
Normal file
@ -0,0 +1,8 @@
|
||||
digraph G {
|
||||
"qt_pi/odom" -> "qt_pi/base_link"[label="Broadcaster: /gazebo\nAverage rate: 30.199 Hz\nMost recent transform: 604.007 ( 0.018 sec old)\nBuffer length: 4.967 sec\n"];
|
||||
"qt_pi/base_link" -> "qt_pi/laser"[label="Broadcaster: /laser_frame\nAverage rate: 30.419 Hz\nMost recent transform: 604.039 ( -0.014 sec old)\nBuffer length: 4.964 sec\n"];
|
||||
edge [style=invis];
|
||||
subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";
|
||||
"Recorded at time: 604.025"[ shape=plaintext ] ;
|
||||
}->"qt_pi/odom";
|
||||
}
|
BIN
gazebo_sim/map/frames.pdf
Normal file
BIN
gazebo_sim/map/frames.pdf
Normal file
Binary file not shown.
BIN
gazebo_sim/map/playground.pgm
Normal file
BIN
gazebo_sim/map/playground.pgm
Normal file
Binary file not shown.
6
gazebo_sim/map/playground.yaml
Normal file
6
gazebo_sim/map/playground.yaml
Normal file
@ -0,0 +1,6 @@
|
||||
image: playground.pgm
|
||||
resolution: 0.050000
|
||||
origin: [-4.000000, -13.000000, 0.000000]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.196
|
2061
gazebo_sim/worlds/qt_pi_laser.world
Normal file
2061
gazebo_sim/worlds/qt_pi_laser.world
Normal file
File diff suppressed because it is too large
Load Diff
Loading…
x
Reference in New Issue
Block a user