Skip to content

Commit 3cd7bee

Browse files
authored
Add files via upload
1 parent 0b96767 commit 3cd7bee

6 files changed

+121
-0
lines changed

costmap_common_params.yaml

+25
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
map_type: costmap #Map type to use, "voxel" or "costmap".
2+
3+
obstacle_range: 2.5 #The maximum range in meters at which to insert obstacles into the costmap using sensor data.
4+
raytrace_range: 3.0 #The maximum range in meters at which to raytrace out obstacles from the map using sensor data.
5+
6+
#The footprint of the robot specified in the robot_base_frame coordinate frame as a list in the format: [ [x1, y1], [x2, y2], ...., [xn, yn] ]. The footprint specification assumes the center point of the robot is at (0.0, 0.0)
7+
footprint: [[-0.40,-0.32],[-0.40,0.32], [0.50, 0.32], [0.50,-0.32]]
8+
9+
10+
resolution: 0.05 #The resolution of the map in meters/cell.
11+
cost_scaling_factor: 20.0 #A scaling factor to apply to cost values during inflation.
12+
inflation_radius: 0.9
13+
14+
#observation_source: A list of observation source names separated by spaces
15+
# /sensor_frame: The frame of the origin of the sensor
16+
# /topic : The topic on which sensor data comes in for this source.
17+
# data_type : The data type associated with the topic.
18+
# clearing : Whether or not this observation should be used to clear out freespace
19+
# marking : Whether or not this observation should be used to mark obstacles.
20+
21+
observation_sources: sonar
22+
sonar: {sensor_frame: /sonar, topic: /rosaria/sonar, data_type: PointCloud, clearing: true, marking: true, max_obstacle_height: 0.4, min_obstacle_height: 0.0}
23+
24+
25+
#More information at http://wiki.ros.org/costmap_2d and http://wiki.ros.org/costmap_2d/flat

global_costmap_params.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
global_costmap:
2+
global_frame: /map #The global frame for the costmap to operate in.
3+
robot_base_frame: /base_link #The name of the frame for the base link of the robot.
4+
update_frequency: 1.0 #The frequency in Hz for the map to be updated.
5+
publish_frequency: 1.0 #The frequency in Hz for the map to be publish display information.
6+
width: 30
7+
height: 30
8+
static_map: true
9+
inflation_radius: 1.0
10+
11+
# More information at http://wiki.ros.org/costmap_2d and http://wiki.ros.org/costmap_2d/flat

global_planner.launch

+24
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
2+
<launch>
3+
4+
<!-- Run the map server -->
5+
<!-- node name="map_server" pkg="map_server" type="map_server" args="$(find p3dx_navigation)/maps/corredor-ct9.yaml" output="screen"/> -->
6+
7+
<!-- Run the map server -->
8+
<node name="map_server" pkg="map_server" type="map_server" args="$(find p3dx_navigation)/maps/orbit_map.yaml" output="screen"/>
9+
10+
<!--- Run AMCL -->
11+
<!--include file="$(find p3dx_navigation)/launch/amcl.launch" />-->
12+
13+
<!--<node name="amcl" pkg="amcl" type="amcl" output="screen"/>-->
14+
15+
<!--- Run move_base with parameters -->
16+
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
17+
<rosparam file="$(find p3dx_navigation)/config/global_planner/costmap_common_params.yaml" command="load" ns="global_costmap" />
18+
<rosparam file="$(find p3dx_navigation)/config/global_planner/costmap_common_params.yaml" command="load" ns="local_costmap" />
19+
<rosparam file="$(find p3dx_navigation)/config/global_planner/local_costmap_params.yaml" command="load" />
20+
<rosparam file="$(find p3dx_navigation)/config/global_planner/global_costmap_params.yaml" command="load" />
21+
<rosparam file="$(find p3dx_navigation)/config/global_planner/move_base_params.yaml" command="load" />
22+
</node>
23+
24+
</launch>

local_costmap_params.yaml

+13
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
local_costmap:
2+
global_frame: /map ##The global frame for the costmap to operate in.
3+
robot_base_frame: /base_link #The name of the frame for the base link of the robot.
4+
update_frequency: 5.0 #The frequency in Hz for the map to be updated.
5+
publish_frequency: 5.0 #The frequency in Hz for the map to be publish display information.
6+
width: 4.0 #The width of the map in meters.
7+
height: 4.0 #The height of the map in meters.
8+
9+
static_map: false #Whether or not to use the static map to initialize the costmap
10+
rolling_window: true #Whether or not to use a rolling window version of the costmap.
11+
resolution: 0.05 #The resolution of the map in meters/cell.
12+
13+
# More information at http://wiki.ros.org/costmap_2d and http://wiki.ros.org/costmap_2d/flat

move_base_params.yaml

+22
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
controller_frequency: 5 #The rate in Hz at which to run the control loop and send velocity commands to the base
2+
3+
TrajectoryPlannerROS:
4+
5+
pdist_scale: 0.9 #The weighting for how much the controller should stay close to the path it was given
6+
7+
max_vel_x: 0.8 # The maximum forward velocity allowed for the base in meters/sec
8+
min_vel_x: 0.03 # The minimum forward velocity allowed for the base in meters/sec.
9+
max_vel_theta: 0.8 #The maximum rotational velocity allowed for the base in radians/sec
10+
min_vel_theta: -0.8 #The minimum rotational velocity allowed for the base in radians/sec
11+
min_in_place_vel_theta: 0.01 # The minimum rotational velocity allowed for the base while performing in-place rotations in radians/sec
12+
13+
acc_lim_theta: 2 #The rotational acceleration limit of the robot in radians/sec^2
14+
acc_lim_x: 0.7 #The x acceleration limit of the robot in meters/sec^2
15+
16+
meter_scoring: true #Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells.
17+
18+
holonomic_robot: false #Determines whether velocity commands are generated for a holonomic or non-holonomic robot.
19+
20+
xy_goal_tolerance: 0.1 # Added by Mike, modified from default value of 0.10
21+
yaw_goal_tolerance: 0.05 # Added by Mike, default is 0.05 (radians)
22+
#More information at http://wiki.ros.org/base_local_planner

nav_grabber.py

+26
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
#!/usr/bin/env python
2+
import rospy
3+
from nav_msgs.msg import Path
4+
5+
rospy.init_node("nav_grabber")
6+
7+
plan_publisher = rospy.Publisher('new_plan', Path, queue_size=10)
8+
9+
rate = rospy.Rate(10.0)
10+
11+
def get_plan():
12+
13+
new_plan = Path()
14+
new_plan.header.frame_id = 'map'
15+
16+
plan = rospy.wait_for_message('move_base/NavfnROS/plan', Path)
17+
print "Publishing a new plan..."
18+
for i in range(len(plan.poses)):
19+
if i % 200 == 0:
20+
new_plan.poses.append(plan.poses[i])
21+
22+
plan_publisher.publish(new_plan)
23+
24+
while not rospy.is_shutdown():
25+
get_plan()
26+
rate.sleep()

0 commit comments

Comments
 (0)