Position model
[Model]
The position model simulates a mobile robot base. It can drive in one of two modes; either differential, i.e. able to control its speed and turn rate by driving left and roght wheels like a Pioneer robot, or omnidirectional, i.e. able to control each of its three axes independently.
Worldfile properties
- Summary and default values
position ( # 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] # model properties )
- Note
- 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.
- Details
- drive "diff", "omni" or "car"
select differential-steer model(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. - 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]
- parameters for the odometry error model used when specifying localization "odom". Each value is the maximum proportion of error in intergrating x, y, and theta velocities to compute odometric position estimate. For each axis, if the the value specified here is E, the actual proportion is chosen at startup at random in the range -E/2 to +E/2. Note that due to rounding errors, setting these values to zero does NOT give you perfect localization - for that you need to choose localization "gps".
Generated on Wed Jul 30 11:36:06 2008 for Stage by 1.4.7