From: Erik Andresen Date: Sat, 11 Jul 2015 17:47:48 +0000 (+0200) Subject: Merge branch 'master' of ssh://vontaene/home/erik_alt/git/ros_wild_thumper X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=860e5f83d540d60b46f4a0f242f007dfd1c0747d;hp=cacb82ac8403db8d5eae119c12faf751ebbe0e71 Merge branch 'master' of ssh://vontaene/home/erik_alt/git/ros_wild_thumper --- diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml new file mode 100644 index 0000000..9cc7b79 --- /dev/null +++ b/config/base_local_planner_params.yaml @@ -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 index 0000000..2ddecc4 --- /dev/null +++ b/config/costmap_common_params.yaml @@ -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 index 0000000..9ea3b6c --- /dev/null +++ b/config/global_costmap_params.yaml @@ -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 index 0000000..e247bea --- /dev/null +++ b/config/local_costmap_params.yaml @@ -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 index 0000000..47c2369 --- /dev/null +++ b/launch/move_base.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +