added navigation costmap files.

This commit is contained in:
yikestone 2019-04-02 02:36:34 +05:30
parent 9f86ea1508
commit 5d132dd630
6 changed files with 71 additions and 0 deletions

View File

@ -0,0 +1,11 @@
TrajectoryPlannerROS:
max_vel_x: 0.45
min_vel_x: 0.1
max_vel_theta: 1.0
min_in_place_vel_theta: 0.4
acc_lim_theta: 3.2
acc_lim_x: 2.5
acc_lim_y: 2.5
holonomic_robot: true

View File

@ -0,0 +1,9 @@
obstacle_range: 100
raytrace_range: 100
footprint: [[0.2, 0.3], [0.2, -0.3], [-0.2, -0.3], [-0.2, 0.3]]
#robot_radius: ir_of_robot
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}

View File

@ -0,0 +1,6 @@
global_costmap:
global_frame: map
robot_base_frame: qt_pi/base_link
update_frequency: 5.0
static_map: false
rolling_window: true

View File

@ -0,0 +1,10 @@
local_costmap:
global_frame: qt_pi/odom
robot_base_frame: qt_pi/base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 15.0
height: 15.0
resolution: 0.05

View File

@ -0,0 +1,20 @@
<launch>
<remap from="odom" to="qt_pi/odom"/>
<remap from="cmd_vel" to="qt_pi/cmd_vel"/>
<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"/>
<param name="controller_patience" value="3.0"/>
<param name="oscillation_timeout" value="30.0"/>
<param name="oscillation_distance" value="0.5"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/costmap_common_params.yaml" command="load" ns="local_costmap"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/local_costmap_params.yaml" command="load"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/global_costmap_params.yaml" command="load"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/base_local_planner_params.yaml" command="load"/>
</node>
</launch>

View File

@ -0,0 +1,15 @@
<launch>
<master auto="start"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(find qt_pi_gazebo_sim)/map/Untitled.pgm 0.05"/>
<include file="$(find amcl)/examples/amcl_diff.launch"/>
<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"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/costmap_common_params.yaml" command="load" ns="local_costmap"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/local_costmap_params.yaml" command="load"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/global_costmap_params.yaml" command="load"/>
<rosparam file="$(find qt_pi_gazebo_sim)/config/base_local_planner_params.yaml" command="load"/>
</node>
</launch>