Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Integrate new orion #17

Open
wants to merge 6 commits into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,6 @@ msg/_*.py
*.dox
*.wikidoc

# Eclipse stuff
.project
.cproject

# QtCreator stuff
CMakeLists.txt.user

Expand Down
46 changes: 46 additions & 0 deletions carmen_2dnav/config/base_local_planner.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
TrajectoryPlannerROS:
# Robot Configuration Parameters
acc_lim_x: 1.0 # aceleration limit in x direction meters/sec^2
acc_lim_y: 0.05 # aceleration limit in y direction meters/sec^2
acc_lim_theta: 0.1 #rotational acceleration limit of the robot in radians/sec^2
max_vel_x: 0.2 #maximum forward velocity allowed for the base in meters/sec
min_vel_x: 0.05 #minimum forward velocity allowed for the base in meters/sec
#(used to overcome friction)
max_vel_theta: 0.15 # max rotational velocity allowed for the base in radians/sec
min_vel_theta: -0.15 # min rotational velocity allowed for the base in radians/sec
min_in_place_rotational_vel: 0.05 #min in-place rotational velocity in rad/sec
escape_vel: -0.15 # Speed used for driving during escapes in meters/sec
holonomic_robot: false # if the robot is holonomic, define also y_vels - strafing velocities
# Goal Tolerance Parameters
yaw_goal_tolerance: 0.20 # tolerance in radians when achieving the goal
xy_goal_tolerance: 0.250 # tolerance in meters when achieving the goal
latch_xy_goal_tolerance: true # set to falso to prevent robot from in-place rotation when
#it reaches the goal xy location
# Forward Simulation Parameters
sim_time: 1.5 # trajectory forward-simulation time in seconds
sim_granularity: 0.25 # the step size, in meters, between points of trajectory
angular_sim_granularity: 0.2 # the step size, in radians, between angular samples of trajectory
vx_samples: 20 # the number of samples to use when exploring the x velocity space
vtheta_samples: 40 # the number of samples to use when exploring the theta velocity space
controller_frequency: 2.0 # the frequency at which this controller will be called in Hz.
# Trajectory scoring parameters
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. Cells are assumed by default (false).
occdist_scale: 0.1 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01
pdist_scale: 0.75 # The weighting for how much the controller should stay close to the path it was given . default 0.6
gdist_scale: 1.0 # The weighting for how much the controller should attempt to reach its local goal, also controls speed default 0.8
heading_lookahead: 0.325 #How far to look ahead in meters when scoring different in-place-rotation trajectories
heading_scoring: false #Whether to score based on the robot's heading to the path or its distance from the path. default false
heading_scoring_timestep: 0.8 #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)
dwa: false #whether to use the DWA or Trajectory Rollout
publish_cost_grid_pc: false # whether or not to publish the cost grid that the planner will use when planning
global_frame_id: odom # the frame to set for the cost_cloud
oscillation_reset_dist: 0.2 #How far the robot must travel in meters before oscillation flags are reset
prune_plan: true #whether or not to eat up the plan as the robot moves along the path
#If set to true, points will fall off the end of the plan once the robot moves 1 meter past them
#See base_local_planner::TrajectoryPlanner Class Reference
esca1pe_reset_dist: 0.2 #The distance the robot must travel before it can leave escape mode
escape_reset_theta: 0.03 # The angle that robot must turn before it can leave escape mode
simple_attractor: false # Enables simple attraction to a goal point
#dwa_local_planner parameters
goal_distance_bias: 10 #In DWA the weighting for how much the controller should attempt to reach its local goal, also controls speed (double, default: 24.0)
path_distance_bias: 22 #In DWA the weighting for how much the controller should stay close to the path it was given (double, default: 32.0)
20 changes: 20 additions & 0 deletions carmen_2dnav/config/costmap_common.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
obstacle_range: 2.5 #range where obstacle is sensed
raytrace_range: 3.0 #range for making sure that there are no obstacles in that direction
#footprint: footprint_padding: 0.1 # planar size of the robot
footprint: [[0.15, 0.15], [0.15, -0.15], [-0.15, -0.15], [-0.15, 0.15]]
robot_radius: 0.30 # perhaps a radius of the robot. I made it bigger that leobot by 0.05
inflation_radius: 0.5 # the radius that assures that there is no collision possibility of different kind. See wiki for more
cost_scaling_factor: 10.0 # setting leobot to be aggressive close to the obstacle by scaling the cost function
transform_tolerance: 0.8 # delay of tf for the case if connection/communicaton with the robot is lost. It is low since loebot will drive in museum
controller_patience: 2.0 # how long to continue operation when controller stops

lidar_scan: {
sensor_frame: laser_link, #where sensor is situated on the robot
observation_persistence: 1.0, #How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.
max_obstacle_height: 2.5, #maximum height of the obstacle
min_obstacle_height: 0.0, #minimum heiht of the obstacle.
data_type: LaserScan, # where is the data obtained from
topic: leobot/laser/scan, # the name of the topic where lidar publishes
marking: true, #shall ROS mark the obstacles
clearing: true #shall ROS clear deprecated marking
}
6 changes: 6 additions & 0 deletions carmen_2dnav/config/global_costmap.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
global_costmap: #The global_frame and the robot_base_frame attributes define the transformation between the map and the robot.
global_frame: map #sets the global frame
robot_base_frame: base_link #frame of the robot
update_frequency: 2.0 #freqency of the map update in Hz
publish_frequency: 1.5 # rate, in Hz, at which the costmap will publish visualization information
static_map: true # whether or not the costmap should initialize itself based on a map served by the map_server
13 changes: 13 additions & 0 deletions carmen_2dnav/config/local_costmap.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 2.0
publish_frequency: 1.5
static_map: false
rolling_window: true
width: 5.0
height: 5.0
resolution: 0.1
transform_tolerance: 0.5
planner_frequency: 1.0
planner_patiente: 5.0
5 changes: 5 additions & 0 deletions carmen_2dnav/map/kitchen.pgm

Large diffs are not rendered by default.

6 changes: 6 additions & 0 deletions carmen_2dnav/map/kitchen.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
image: kitchen.pgm
resolution: 0.025000
origin: [-5.000000, -5.000000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196
Loading