]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added move_base
authorErik Andresen <erik@vontaene.de>
Sat, 11 Jul 2015 17:47:37 +0000 (19:47 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 11 Jul 2015 17:47:37 +0000 (19:47 +0200)
config/base_local_planner_params.yaml [new file with mode: 0644]
config/costmap_common_params.yaml [new file with mode: 0644]
config/global_costmap_params.yaml [new file with mode: 0644]
config/local_costmap_params.yaml [new file with mode: 0644]
launch/move_base.launch [new file with mode: 0644]

diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml
new file mode 100644 (file)
index 0000000..9cc7b79
--- /dev/null
@@ -0,0 +1,13 @@
+TrajectoryPlannerROS:
+  min_vel_x: 0.1
+  max_vel_x: 0.3
+  min_vel_theta: -1.0
+  max_vel_theta: 1.0
+  min_in_place_vel_theta: 0.4
+
+  acc_lim_x: 2.5
+  acc_lim_y: 0.0
+  acc_lim_theta: 3.2
+
+  holonomic_robot: false
+  meter_scoring: true
diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml
new file mode 100644 (file)
index 0000000..2ddecc4
--- /dev/null
@@ -0,0 +1,8 @@
+footprint: [[0.14, 0.16], [-0.14, 0.16], [-0.14, -0.16], [0.14, -0.16]]
+inflation_radius: 0.55
+
+obstacle_layer:
+  observation_sources: laser_scan_sensor
+  obstacle_range: 2.5
+  raytrace_range: 3.0
+  laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
diff --git a/config/global_costmap_params.yaml b/config/global_costmap_params.yaml
new file mode 100644 (file)
index 0000000..9ea3b6c
--- /dev/null
@@ -0,0 +1,9 @@
+global_costmap:
+  global_frame: /map
+  robot_base_frame: base_footprint
+  update_frequency: 5.0
+  static_map: true
+  plugins:
+  - {name: static_layer, type: 'costmap_2d::StaticLayer'}
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
diff --git a/config/local_costmap_params.yaml b/config/local_costmap_params.yaml
new file mode 100644 (file)
index 0000000..e247bea
--- /dev/null
@@ -0,0 +1,18 @@
+local_costmap:
+  global_frame: odom
+  robot_base_frame: base_footprint
+  update_frequency: 5.0
+  publish_frequency: 2.0
+  static_map: false
+  rolling_window: true
+  width: 10.0
+  height: 10.0
+  resolution: 0.05
+  plugins:
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  #- {name: sonar_layer,   type: "range_sensor_layer::RangeSensorLayer"}
+  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
+
+  sonar_layer:
+    topics: ["range_forward", "range_backward", "range_left", "range_right"]
+    no_readings_timeout: 1.0
diff --git a/launch/move_base.launch b/launch/move_base.launch
new file mode 100644 (file)
index 0000000..47c2369
--- /dev/null
@@ -0,0 +1,33 @@
+<?xml version="1.0"?>
+<launch>
+       <arg name="slam_gmapping" default="false" />
+       <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
+
+       <!-- Run the map server -->
+       <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+
+       <!-- Run AMCL -->
+       <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
+       <param name="amcl/base_frame_id" value="base_footprint" />
+
+       <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
+               <param name="scan" value="scan" />
+               <param name="delta" value="0.01" />
+               <param name="map_update_interval" value="30" />
+               <param name="linearUpdate" value="0.5" />
+               <param name="angularUpdate" value="0.25" />
+               <param name="xmin" value="-1.0"/>
+               <param name="ymin" value="-1.0"/>
+               <param name="xmax" value="1.0"/>
+               <param name="ymax" value="1.0"/>
+               <param name="odom_frame" value="odom"/>
+       </node>
+
+       <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" unless="$(arg slam_gmapping)">
+               <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+               <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
+               <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
+               <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
+       </node>
+</launch>