Update of /cvsroot/playerstage/code/stage/worlds
In directory sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv8601
Modified Files:
sick.inc
Added Files:
mbicp.cfg mbicp.world p3at.inc p3dx.inc pioneerBase.inc
Log Message:
added mbicp examples
--- NEW FILE: mbicp.cfg ---
driver
(
name "stage"
provides ["simulation:0" ]
plugin "libstageplugin"
# load the named file into the simulator
worldfile "mbicp.world"
)
driver
(
name "stage"
provides ["position2d:0" "laser:0" "sonar:0"]
model "robot1"
)
driver
(
name "laserposeinterpolator"
provides ["laser:1"]
requires ["laser:0" "position2d:0"]
)
driver
(
name "mbicp"
provides ["position2d:1"]
requires ["position2d:0" "laser:1"]
max_laser_range 7.9
laserPose_x 0.16
laserPose_y 0
laserPose_th 0
radial_window 0.09
angular_window 0.523333333
L 3.00
laserStep 1
MaxDistInter 0.5
filter 0.95
ProjectionFilter 1
AsocError 0.1
MaxIter 500
errorRatio 0.0001
errx_out 0.0001
erry_out 0.0001
errt_out 0.0001
IterSmoothConv 2
)
driver
(
name "nd"
provides ["position2d:2"]
requires ["output:::position2d:0" "input:::position2d:0" "laser:0" "sonar:0"]
max_speed [0.7 100.0]
min_speed [0.1 10.0]
goal_tol [0.3 15.0]
wait_on_stall 1
rotate_stuck_time 5.0
translate_stuck_time 5.0
translate_stuck_dist 0.15
translate_stuck_angle 10.0
avoid_dist 0.4
safety_dist 0.0
laser_buffer 20
sonar_buffer 20
)
Index: sick.inc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/worlds/sick.inc,v
retrieving revision 1.1
retrieving revision 1.2
diff -C2 -d -r1.1 -r1.2
*** sick.inc 27 Jul 2005 18:37:08 -0000 1.1
--- sick.inc 21 Aug 2007 23:28:31 -0000 1.2
***************
*** 11,12 ****
--- 11,13 ----
)
+ define sicklms200 sick_laser ()
--- NEW FILE: p3at.inc ---
# Desc: Device definitions for P3AT Activemedia robots.
# Author: Luis Riazuelo [EMAIL PROTECTED]
# Date: 13 Jun 2007
# defines sick laser
include "pioneerBase.inc"
include "sick.inc"
# The Pioneer3AT sonar array
define p3at_sonar ranger
(
scount 16
# define the pose of each transducer [xpos ypos heading]
spose[0] [0.147 0.136 90]
spose[1] [0.193 0.119 50]
spose[2] [0.227 0.079 30]
spose[3] [0.245 0.027 10]
spose[4] [0.245 -0.027 -10]
spose[5] [0.227 -0.079 -30]
spose[6] [0.193 -0.119 -50]
spose[7] [0.147 -0.136 -90]
spose[8] [-0.144 -0.136 -90]
spose[9] [-0.189 -0.119 -130]
spose[10] [-0.223 -0.079 -150]
spose[11] [-0.241 -0.027 -170]
spose[12] [-0.241 0.027 170]
spose[13] [-0.223 0.079 150]
spose[14] [-0.189 0.119 130]
spose[15] [-0.144 0.136 90]
# define the field of view of each transducer [range_min range_max view_angle]
sview [0.1 5.0 30] # min (m), max (m), field of view (deg)
# define the size of each transducer [xsize ysize] in meters
ssize [0.01 0.04]
)
# The Pioneer3AT standard configuration
define pioneer3at pioneerBase
(
# Actual size
size [0.626 0.505]
# The pioneer's center of rotation is offset from its center of area
origin [-0.04465 0.0 0.0]
# Estimated mass in KG
mass 40.0
# Body shape:
polygons 1
polygon[0].points 8
polygon[0].point[0] [-0.18 0.313]
polygon[0].point[1] [0.18 0.313]
polygon[0].point[2] [0.2525 0.18]
polygon[0].point[3] [0.2525 -0.18]
polygon[0].point[4] [0.18 -0.313]
polygon[0].point[5] [-0.18 -0.313]
polygon[0].point[6] [-0.2525 -0.18]
polygon[0].point[7] [-0.2525 0.18]
# Use the sonar array defined above
p3at_sonar()
# Use the laser lms200
sicklms200( pose [0.16 0 0] )
)
--- NEW FILE: pioneerBase.inc ---
# Common parameters to all pioneers
define pioneerBase position (
color "red" # Default color.
drive "diff" # Differential steering model.
gui_nose 1 # Draw a nose on the robot so we can see which
way it points
obstacle_return 1 # Can hit things.
laser_return 0 # Robot body seen by other lasers. If you want
to model
# real pioneers with SICK lasers, where the laser is
# taller than the robot.
ranger_return 1 # Seen by other sonar.
blobfinder_return 1 # Seen by other blobfinders.
fiducial_return 2 # Seen as "2" by other fiducial sensors.
# localization "odom" # Change to "gps" to have impossibly
perfect, global odometry
# odom_error [ 0.05 0.05 0.1 ] # Odometry error or slip in X, Y and
Theta
# (Uniform random distribution)
localization "gps"
localization_origin [0 0 0] # Start odometry at (0, 0, 0).
)
--- NEW FILE: p3dx.inc ---
# Desc: Device definitions for P3DX Activemedia robots.
# Author: Luis Riazuelo [EMAIL PROTECTED]
# Date: 13 Jun 2007
# defines sick laser
include "pioneerBase.inc"
include "sick.inc"
# The Pioneer3DX sonar array
define p3dx_sonar ranger
(
scount 16
# define the pose of each transducer [xpos ypos heading]
spose[0] [ 0.069 0.136 90 ]
spose[1] [ 0.114 0.119 50 ]
spose[2] [ 0.148 0.078 30 ]
spose[3] [ 0.166 0.027 10 ]
spose[4] [ 0.166 -0.027 -10 ]
spose[5] [ 0.148 -0.078 -30 ]
spose[6] [ 0.114 -0.119 -50 ]
spose[7] [ 0.069 -0.136 -90 ]
spose[8] [ -0.157 -0.136 -90 ]
spose[9] [ -0.203 -0.119 -130 ]
spose[10] [ -0.237 -0.078 -150 ]
spose[11] [ -0.255 -0.027 -170 ]
spose[12] [ -0.255 0.027 170 ]
spose[13] [ -0.237 0.078 150 ]
spose[14] [ -0.103 0.119 130 ]
spose[15] [ -0.157 0.136 90 ]
# define the field of view of each transducer [range_min range_max view_angle]
sview [0.1 5.0 30] # min (m), max (m), field of view (deg)
# define the size of each transducer [xsize ysize] in meters
ssize [0.01 0.04]
)
# The Pioneer3DX standard configuration
define pioneer3dx pioneerBase
(
# Actual size
size [0.511 0.4]
# The pioneer's center of rotation is offset from its center of area
origin [-0.04465 0.0 0.0]
# Estimated mass in KG
mass 23.0
# Body shape:
polygons 1
polygon[0].points 8
polygon[0].point[0] [-0.12 0.2555]
polygon[0].point[1] [0.12 0.2555]
polygon[0].point[2] [0.2 0.12]
polygon[0].point[3] [0.2 -0.12]
polygon[0].point[4] [0.12 -0.2555]
polygon[0].point[5] [-0.12 -0.2555]
polygon[0].point[6] [-0.2 -0.12]
polygon[0].point[7] [-0.2 0.12]
# Use the sonar array defined above
p3dx_sonar()
# Use the laser lms200
sicklms200( pose [0.12 0 0] )
)
--- NEW FILE: mbicp.world ---
# defines Pioneer-like robots
include "p3dx.inc"
# defines 'map' object used for floorplans
include "map.inc"
size [30 20]
resolution 0.02
gui_interval 20
# configure the GUI window
window
(
size [ 800 600.000 ]
center [0.0 0.0]
scale 0.04
)
map
(
bitmap "bitmaps/mbicp.png"
size [28 10]
name "pruebaScan"
)
# create a robot
pioneer3dx
(
name "robot1"
color "red"
pose [8 0 180]
)
-------------------------------------------------------------------------
This SF.net email is sponsored by: Splunk Inc.
Still grepping through log files to find problems? Stop.
Now Search log events and configuration files using AJAX and a browser.
Download your FREE copy of Splunk now >> http://get.splunk.com/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit