Revision: 6837 http://playerstage.svn.sourceforge.net/playerstage/?rev=6837&view=rev Author: jeremy_asher Date: 2008-07-10 14:49:23 -0700 (Thu, 10 Jul 2008)
Log Message: ----------- Worldfile documentation updates Modified Paths: -------------- code/stage/trunk/libstage/model.cc code/stage/trunk/libstage/model_blobfinder.cc code/stage/trunk/libstage/model_camera.cc code/stage/trunk/libstage/model_fiducial.cc code/stage/trunk/libstage/model_laser.cc code/stage/trunk/libstage/model_position.cc code/stage/trunk/libstage/model_ranger.cc Modified: code/stage/trunk/libstage/model.cc =================================================================== --- code/stage/trunk/libstage/model.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -15,17 +15,13 @@ @verbatim model ( - pose [ 0 0 0 0 ] + pose [ 0.0 0.0 0.0 0.0 ] size [ 0.1 0.1 0.1 ] - origin [ 0 0 0 0 ] - velocity [ 0 0 0 0 ] + origin [ 0.0 0.0 0.0 0.0 ] + velocity [ 0.0 0.0 0.0 0.0 ] color "red" - color_rgba [ 0 0 0 1 ] - - boundary 0 - blocks -1 - mass 10 + color_rgba [ 0.0 0.0 0.0 1.0 ] # determine how the model appears in various sensors fiducial_return 0 @@ -36,21 +32,19 @@ laser_return LaserVisible gripper_return 0 - # GUI properties gui_nose 0 gui_grid 0 gui_outline 1 ( was gui_boundary? ) gui_movemask 0 top level or (STG_MOVE_TRANS | STG_MOVE_ROT); + boundary 0 + blocks -1 + mass 10.0 bitmap "" - ctrl "" - map_resolution 0.1 - say "" - alwayson 0 ) @endverbatim Modified: code/stage/trunk/libstage/model_blobfinder.cc =================================================================== --- code/stage/trunk/libstage/model_blobfinder.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_blobfinder.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -46,38 +46,32 @@ @par Summary and default values @verbatim -ptz( -# blobfinder MUST be a child of a PTZ model blobfinder ( -# blobfinder properties -colors_count 6 -colors ["red" "green" "blue" "cyan" "yellow" "magenta" ] -range 8.0 -ptz[0 0 60.0] -image[80 60] + # blobfinder properties + colors_count 0 + colors [ ] + image[ 80 60 ] + range 12.0 + fov 3.14159/3.0 + pan 0.0 -# model properties -size3 [0 0 0] + # model properties + size [ 0.0 0.0 0.0 ] ) -) @endverbatim @par Details -- colors_count int -- number of colors being tracked -- colors [ string ... ] -- define the colors detected in each channel, using color names from the X11-style color database -The number of strings should match colors_count. -- image [int int] -- [width height] -- dimensions of the image in pixels. This determines the blobfinder's -resolution -- ptz [float float float] -- [pan_angle tilt_angle zoom_angle] -- control the panning, tilt and fov angle (zoom) of the blobfinder. Tilt angle currently has no effect. -- range float -- maximum range of the sensor in meters. +- colors_count <int>\n + number of colors being tracked +- colors [ col1:<string> col2:<string> ... ]\n + A list of quoted strings defining the colors detected in each channel, using color names from the X11-style color database (ex. "black", "red"). + The number of strings should match colors_count. +- image [ width:<int> height:<int> ]\n + dimensions of the image in pixels. This determines the blobfinder's resolution +- range <float>\n + maximum range of the sensor in meters. + */ Modified: code/stage/trunk/libstage/model_camera.cc =================================================================== --- code/stage/trunk/libstage/model_camera.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_camera.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -19,59 +19,61 @@ Option StgModelCamera::showCameraData( "Show Camera Data", "show_camera", "", true ); -static const stg_size_t DEFAULT_SIZE = {0.1, 0.07, 0.05 }; +static const stg_size_t DEFAULT_SIZE = { 0.1, 0.07, 0.05 }; static const char DEFAULT_GEOM_COLOR[] = "black"; +static const float DEFAULT_HFOV = 70; +static const float DEFAULT_VFOV = 40; /** - @ingroup model - @defgroup model_camera Camera model - The camera model simulates a camera - - API: Stg::StgModelCamera - - <h2>Worldfile properties</h2> - - @par Summary and default values - - @verbatim - camera - ( - # laser properties - width 32 - height 32 - range_min 0.0 - range_max 8.0 - horizfov 60.0 - vertfov 60.0 - yaw 0.0 - pitch 90.0 - - # model properties - size [0.15 0.15] - color "black" - watts 100.0 # TODO find watts for sony pan-tilt camera - ) - @endverbatim - - @par Details - - width int - - the number of pixel samples - - height int - - the number of pixel samples - - range_min float - - the minimum range reported by the camera, in meters. Objects closer than this will not be displayed. The smaller the number, the less persision in depth - don't set this value too close to 0. - - range_max float - - the maximum range reported by the camera, in meters. Objects farther than this will not be displayed. - - horizfov float - - angle, in degrees, for the horizontal field of view. - - vertfov float - - angle, in degrees, for the vertical field of view. - - yaw float - - angle, in degrees, where the camera is panned to. - - pitch float - - angle, in degrees, where the camera is tilted to. - */ [EMAIL PROTECTED] model [EMAIL PROTECTED] model_camera Camera model +The camera model simulates a camera +API: Stg::StgModelCamera + +<h2>Worldfile properties</h2> + [EMAIL PROTECTED] Summary and default values + [EMAIL PROTECTED] +camera +( + # laser properties + width 32 + height 32 + range_min 0.2 + range_max 8.0 + horizfov 70.0 + vertfov 40.0 + yaw 0.0 + pitch 0.0 + + # model properties + size [ 0.1 0.07 0.05 ] + color "black" + watts 100.0 # TODO find watts for sony pan-tilt camera +) [EMAIL PROTECTED] + [EMAIL PROTECTED] Details +- width <int>\n + the number of pixel samples +- height <int>\n + the number of pixel samples +- range_min <float>\n + the minimum range reported by the camera, in meters. Objects closer than this will not be displayed. The smaller the number, the less persision in depth - don't set this value too close to 0. +- range_max <float>\n + the maximum range reported by the camera, in meters. Objects farther than this will not be displayed. +- horizfov <float>\n + angle, in degrees, for the horizontal field of view. +- vertfov <float>\n + angle, in degrees, for the vertical field of view. +- yaw <float>\n + angle, in degrees, where the camera is panned to. +- pitch <float>\n + angle, in degrees, where the camera is tilted to. +*/ + //caclulate the corss product, and store results in the first vertex void cross( float& x1, float& y1, float& z1, float x2, float y2, float z2 ) { @@ -146,9 +148,13 @@ { StgModel::Load(); - _camera.setFov( wf->ReadLength( wf_entity, "horizfov", _camera.horizFov() ), wf->ReadLength( wf_entity, "vertfov", _camera.vertFov() ) ); + float horizFov = wf->ReadFloat( wf_entity, "horizfov", DEFAULT_HFOV ); + float vertFov = wf->ReadFloat( wf_entity, "vertfov", DEFAULT_VFOV ); + _camera.setFov( horizFov, vertFov ); - _camera.setClip( wf->ReadLength( wf_entity, "range_min", CAMERA_NEAR_CLIP ), wf->ReadLength( wf_entity, "range_max", CAMERA_FAR_CLIP ) ); + float range_min = wf->ReadLength( wf_entity, "range_min", CAMERA_NEAR_CLIP ); + float range_max = wf->ReadLength( wf_entity, "range_max", CAMERA_FAR_CLIP ); + _camera.setClip( range_min, range_max ); _yaw_offset = wf->ReadFloat( wf_entity, "yaw", _yaw_offset ); _pitch_offset = wf->ReadFloat( wf_entity, "pitch", _pitch_offset ); Modified: code/stage/trunk/libstage/model_fiducial.cc =================================================================== --- code/stage/trunk/libstage/model_fiducial.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_fiducial.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -40,26 +40,26 @@ @verbatim fiducialfinder ( -# fiducialfinder properties -range_min 0.0 -range_max 8.0 -range_max_id 5.0 -fov 180.0 + # fiducialfinder properties + range_min 0.0 + range_max 8.0 + range_max_id 5.0 + fov 3.14159 -# model properties -size [0 0] + # model properties + size [ 0.1 0.1 0.1 ] ) @endverbatim @par Details -- range_min float -- the minimum range reported by the sensor, in meters. The sensor will detect objects closer than this, but report their range as the minimum. -- range_max float -- the maximum range at which the sensor can detect a fiducial, in meters. The sensor may not be able to uinquely identify the fiducial, depending on the value of range_max_id. -- range_max_id float -- the maximum range at which the sensor can detect the ID of a fiducial, in meters. -- fov float -- the angular field of view of the scanner, in degrees. +- range_min <float>\n + the minimum range reported by the sensor, in meters. The sensor will detect objects closer than this, but report their range as the minimum. +- range_max <float>\n + the maximum range at which the sensor can detect a fiducial, in meters. The sensor may not be able to uinquely identify the fiducial, depending on the value of range_max_id. +- range_max_id <float>\n + the maximum range at which the sensor can detect the ID of a fiducial, in meters. +- fov <float> + the angular field of view of the scanner, in radians. */ Modified: code/stage/trunk/libstage/model_laser.cc =================================================================== --- code/stage/trunk/libstage/model_laser.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_laser.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -37,43 +37,44 @@ Option StgModelLaser::showLaserStrikes( "Show Laser Data", "show_laser_strikes", "", false ); /** - @ingroup model - @defgroup model_laser Laser model - The laser model simulates a scanning laser rangefinder [EMAIL PROTECTED] model [EMAIL PROTECTED] model_laser Laser model +The laser model simulates a scanning laser rangefinder - API: Stg::StgModelLaser +API: Stg::StgModelLaser - <h2>Worldfile properties</h2> +<h2>Worldfile properties</h2> - @par Summary and default values [EMAIL PROTECTED] Summary and default values - @verbatim - laser - ( - # laser properties - samples 180 - range_min 0.0 - range_max 8.0 - fov 180.0 [EMAIL PROTECTED] +laser +( + # laser properties + samples 180 + range_min 0.0 + range_max 8.0 + fov 3.14159 + laser_sample_skip 1 - # model properties - size [0.15 0.15] - color "blue" - watts 17.5 # approximately correct for SICK LMS200 - ) - @endverbatim + # model properties + size [ 0.15 0.15 0.2 ] + color "blue" + watts 17.5 # approximately correct for SICK LMS200 +) [EMAIL PROTECTED] - @par Details - - samples int - - the number of laser samples per scan - - range_min float - - the minimum range reported by the scanner, in meters. The scanner will detect objects closer than this, but report their range as the minimum. - - range_max float - - the maximum range reported by the scanner, in meters. The scanner will not detect objects beyond this range. - - fov float - - the angular field of view of the scanner, in degrees. - - laser_sample_skip - - Only calculate the true range of every nth laser sample. The missing samples are filled in with a linear interpolation. Generally it would be better to use fewer samples, but some (poorly implemented!) programs expect a fixed number of samples. Setting this number > 1 allows you to reduce the amount of computation required for your fixed-size laser vector. [EMAIL PROTECTED] Details +- samples <int>\n + the number of laser samples per scan +- range_min <float>\n + the minimum range reported by the scanner, in meters. The scanner will detect objects closer than this, but report their range as the minimum. +- range_max <float>\n + the maximum range reported by the scanner, in meters. The scanner will not detect objects beyond this range. +- fov <float>\n + the angular field of view of the scanner, in radians. +- laser_sample_skip <int>\n + Only calculate the true range of every nth laser sample. The missing samples are filled in with a linear interpolation. Generally it would be better to use fewer samples, but some (poorly implemented!) programs expect a fixed number of samples. Setting this number > 1 allows you to reduce the amount of computation required for your fixed-size laser vector. */ StgModelLaser::StgModelLaser( StgWorld* world, Modified: code/stage/trunk/libstage/model_position.cc =================================================================== --- code/stage/trunk/libstage/model_position.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_position.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -20,15 +20,15 @@ #include "stage_internal.hh" /** - @ingroup model - @defgroup model_position Position model [EMAIL PROTECTED] model [EMAIL PROTECTED] model_position Position model - The position model simulates a - mobile robot base. It can drive in one of two modes; either - <i>differential</i>, i.e. able to control its speed and turn rate by - driving left and roght wheels like a Pioneer robot, or - <i>omnidirectional</i>, i.e. able to control each of its three axes - independently. +The position model simulates a +mobile robot base. It can drive in one of two modes; either +<i>differential</i>, i.e. able to control its speed and turn rate by +driving left and roght wheels like a Pioneer robot, or +<i>omnidirectional</i>, i.e. able to control each of its three axes +independently. API: Stg::StgModelPosition @@ -39,16 +39,16 @@ @verbatim position ( -# position properties -drive "diff" -localization "gps" -localization_origin [ <defaults to model's start pose> ] + # position properties + drive "" + localization "" + localization_origin [ <defaults to model's start pose> ] -# odometry error model parameters, -# only used if localization is set to "odom" -odom_error [0.03 0.03 0.05] + # odometry error model parameters, + # only used if localization is set to "odom" + odom_error [0.03 0.03 0.05] -# model properties + # model properties ) @endverbatim @@ -56,10 +56,10 @@ Since Stage-1.6.5 the odom property has been removed. Stage will generate a warning if odom is defined in your worldfile. See localization_origin instead. @par Details -- drive "diff", "omni" or "car" -- select differential-steer mode (like a Pioneer), omnidirectional mode or carlike (velocity and steering angle). -- localization "gps" or "odom" -- if "gps" the position model reports its position with perfect accuracy. If "odom", a simple odometry model is used and position data drifts from the ground truth over time. The odometry model is parameterized by the odom_error property. +- drive "diff", "omni" or "car"\n + select differential-steer model(like a Pioneer), omnidirectional mode or carlike (velocity and steering angle). +- localization "gps" or "odom"\n + if "gps" the position model reports its position with perfect accuracy. If "odom", a simple odometry model is used and position data drifts from the ground truth over time. The odometry model is parameterized by the odom_error property. - localization_origin [x y theta] - set the origin of the localization coordinate system. By default, this is copied from the model's initial pose, so the robot reports its position relative to the place it started out. Tip: If localization_origin is set to [0 0 0] and localization is "gps", the model will return its true global position. This is unrealistic, but useful if you want to abstract away the details of localization. Be prepared to justify the use of this mode in your research! - odom_error [x y theta] Modified: code/stage/trunk/libstage/model_ranger.cc =================================================================== --- code/stage/trunk/libstage/model_ranger.cc 2008-07-10 18:32:37 UTC (rev 6836) +++ code/stage/trunk/libstage/model_ranger.cc 2008-07-10 21:49:23 UTC (rev 6837) @@ -25,30 +25,30 @@ @verbatim ranger ( -# ranger properties -scount 16 -spose[0] [? ? ?] -spose[1] [? ? ?] -spose[2] [? ? ?] -spose[3] [? ? ?] -spose[4] [? ? ?] -spose[5] [? ? ?] -spose[6] [? ? ?] -spose[7] [? ? ?] -spose[8] [? ? ?] -spose[9] [? ? ?] -spose[10] [? ? ?] -spose[11] [? ? ?] -spose[12] [? ? ?] -spose[13] [? ? ?] -spose[14] [? ? ?] -spose[15] [? ? ?] + # ranger properties + scount 16 + spose[0] [? ? ?] + spose[1] [? ? ?] + spose[2] [? ? ?] + spose[3] [? ? ?] + spose[4] [? ? ?] + spose[5] [? ? ?] + spose[6] [? ? ?] + spose[7] [? ? ?] + spose[8] [? ? ?] + spose[9] [? ? ?] + spose[10] [? ? ?] + spose[11] [? ? ?] + spose[12] [? ? ?] + spose[13] [? ? ?] + spose[14] [? ? ?] + spose[15] [? ? ?] -ssize [0.01 0.03] -sview [0.0 5.0 5.0] + ssize [0.01 0.03] + sview [0.0 5.0 5.0] -# model properties -watts 2.0 + # model properties + watts 2.0 ) @endverbatim @@ -57,11 +57,10 @@ The ranger model allows configuration of the pose, size and view parameters of each transducer seperately (using spose[index], ssize[index] and sview[index]). However, most users will set a common size and view (using ssize and sview), and just specify individual transducer poses. @par Details -- scount int -- the number of range transducers -- spose[\<transducer index\>] [float float float] -- [x y theta] -- pose of the transducer relative to its parent. +- scount <int>\n + the number of range transducers +- spose[\<transducer index\>] [ x:<float> y:<float> theta:<float> ]\n + pose of the transducer relative to its parent. - ssize [float float] - [x y] - size in meters. Has no effect on the data, but controls how the sensor looks in the Stage window. This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- Sponsored by: SourceForge.net Community Choice Awards: VOTE NOW! Studies have shown that voting for your favorite open source project, along with a healthy diet, reduces your potential for chronic lameness and boredom. Vote Now at http://www.sourceforge.net/community/cca08 _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit