Poseidon is a localization framework that utilizes plugins to support multiple localization algorithms that are based on a particle filter. There are two different kind of plugins. The map model plugin is used for global pose sampling and providing a reference frame for localization. The sensor model plugins update the weights of the particles as well as their positions based on sensor readings. Sensor plugins can be switched at runtime. The standard plugins provide a grid map model for 2d occupancy grid maps and a range scan sensor plugin for localization in occupancy grid maps. Both standard plugins are based on the functionality of the AMCL domain and will realize completely the same behavior. Alternative plugins could provide localization using wifi, magnetic sensors or markers.
Channels
Subscribed
Published
Services
Required
- IRobotModelProvider
boost::shared_ptr<mira::robot::RobotModel> getRobotModel() The provided model must be a subclass of mira::robot::ProbabilisticMotionModel and is used for motion sampling.
Published
- void setMute(bool);
- Mutes/Unmutes the localization system (mute = no transform is published)
- void enableSensor(const std::string&)
- Disables all sensors and enables the specified on (name of the sensor must be its class identifier e.g. mira::localization::RangeScanSensor)
- ILocalization
- void setInitPose(const PoseCov2&)
- Initializes localization at the given pose. Pose is assumed to be in the reference frame.
- void setInitPose(const PoseCov2&, const std::string&)
- Initializes localization at the given pose using the frame of the pose.
Transforms
Each time a resampling was performed a transform for frame OdometryFrame is published indirectly by updating the transform link between the frame id of the odometry channel and the reference frame given by the map model.
Parameters
- ModelProvider (std::string)
The name of the service that provides a robot model. If empty, a suitable service is chosen automatically.
- InitialPose (mira::PoseCov2)
Pose used for initialization at startup.
- UpdateMinDistance (float) [property]
Minimum distance driven in meter before updating the pose.
- UpdateMinRotation (float) [property]
Minimum degrees rotated before updating the pose.
- PFError (float)
Population size parameter. Maximum allowed error between the true distribution and the estimated distribution.
- PFZ (float)
Population size parameter. Upper standard normal quantile for (1 - p), where p is the probability that the error on the estimated distribution will be less than PFError.
- RecoveryAlphaSlow (float)
Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses.
- RecoveryAlphaFast (float)
Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses.
- ResampleInterval (int) [property]
Number of filter updates required before resampling.
- Sensors (std::vector<mira::localization::SensorPtr>) [property]
Sensor plugins to use for resampling and updating weights.
- MapModel (mira::localization::MapModelPtr) [property]
Map model plugin to use for pose generation and reference frame.
- MinParticles (int)
Minimum number of particles.
- MaxParticles (int)
Maximum number of particles.
- Mute (bool) [property]
If true, output of transform is disabled.
Map model plugins
Map model plugins provide an interface for sampling random global poses. They use the underlying map to exclude poses that fall in areas of obstacles or would mean the robots footprint/shape/bounding box collides with the environment. They also provide a reference frame for localization (e.g. the frame of the used map).
GridMapModel
This model uses 2d occupancy grid maps and the currently used robot model to exclude pose samples that would mean the robots footprint collides with the environment.
Channels
Parameters
- CollisionTest (mira::model::CollisionTest)
Collision test object for excluding sample poses based on collision
Transforms
Adds a link from OdometryFrame to the frame of the used map
Sensor plugins
Sensor plugins are used to update the weights of the particles according to some sensor input.
RangeScanSensor
This plugin computes a matching factor of current range scan sensor readings with an existing map for each particle and updates the weights based on this factor. It provides two different matching models.
- The beam model calculates for each particle and a number of scans the distance of the scan that would be observed if the robot were located at the particles position in the map. It compares this distance with the measured distance from the range sensor and computes a matching factor (difference).
- The likelihood model pre-computes a map by applying a distance transform on the original map. Each cell then contains the distance to the nearest obstacle. It calculates for each particle the map cell where the scan based on the measurement of the range sensor would fall into if the robot were located at the particles position. As the value of the cell at this position contains the distance to the nearest obstacle it serves as a the matching factor. This model is faster and takes less performance than the beam model.
Channels
Parameters
- RangeChannels (std::vector<std::string>)
Connected range scan channels
- SensorModel (int)
Used sensor model (0=beam, 1=likelihood)
- MaxBeams (int)
Maximum number of beams (range scans) used from the range sensor reading
- MinRange (float)
Minimum used range in meter
- MaxRange" (float)
Maximum used range in meter
- ZHit" (float)
Mixture param for the components of the model
- Zshort" (float)
Mixture param for the components of the model (only beam model)
- Zmax" (float)
Mixture param for the components of the model
- Zrand" (float)
Mixture param for the components of the model
- SigmaHit" (float)
Stddev of gaussian model for range scan hits
- LambdaShort" (float)
Decay rate of exponential model for short readings (only beam model)
- LikelihoodMaxDist" (float)
Max obstacle distance used when range reading would be out of map bounds (only likelyhood model)