Jafar
|
SLAM (Simultaneous Localization And Mapping) is a fundamental problem for robotics.
The module slam implements several algorithms:
Currently, sizeless points, iinverse-depth points and Plucker lines can be used as features.
# # setup # # create a Slam object set slamEkf [slam::new_SlamEkf 350 6 6] # optionnaly change the map manager # $slamEkf setMapManager [slam::new_LocalMapManager $slamEkf 40 3] # $slamEkf setMapManager [slam::new_GlobalMapManager $slamEkf 3 3.0] # covariance update method (DEFAULT, STANDARD, JOSEPH) [$slamEkf getFilter] setCovUpdateType $filter::BaseKalmanFilter_STANDARD # consistency check method [$slamEkf getFilter] setupConsistencyCheck $::filter::BaseKalmanFilter_CONSISTENCY_EXCEPTION 10.0 # create a landmark model set ptModel [slam::new_PointFeatureModel] # create an associated observe model set ptObsModel [slam::new_PolarPointFeatureObserveModel $ptModel] $ptObsModel setNoiseValues 0.1 [jmath::degToRad 2] [jmath::degToRad 2] # add the defined sensor to Slam $slamEkf setSensor $ptObsModel # set the robot to sensor t3d set robotToSensor [jmath::new_vec 6] jmath::setValue $robotToSensor "(0,0,1.0,[jmath::degToRad 90],0,0)" $slamEkf setRobotToSensor $robotToSensor # create a prediction model set odoPredictModel [slam::new_Odo3dPredictModel] [$odoPredictModel cget -odoNoiseModel] set [expr pow(0.05,2)] 0 [expr pow(0.05,2)] 0 # # run # # predict with command u [v,w] $slamEkf predict $predictModel $u # update FIXME
# create and initialize the slam object slamEkf = Slam::SlamEkf.new(350, 6, 6) slamEkf.getFilter.setCovUpdateType(Filter::BaseKalmanFilter::STANDARD) slamEkf.getFilter.setupConsistencyCheck(Filter::BaseKalmanFilter::CONSISTENCY_EXCEPTION, 10.0) # create a landmark model ptModel = Slam::PointFeatureModel.new # create an associated observe model ptObsModel = Slam::PolarPointFeatureObserveModel.new( ptModel ) ptObsModel.setNoiseValues( 0.1, Jmath::degToRad(2), Jmath::degToRad(2)) # add the defined sensor to Slam slamEkf.setSensor(ptObsModel) # set the robot to sensor t3d robotToSensor = Jmath::Vec.new(6) Jmath::setValue(robotToSensor, "(0,0,1.0,#{Jmath::degToRad(90)},0,0)") slamEkf.setRobotToSensor(robotToSensor) # create a prediction model odoPredictModel = Slam::Odo3dPredictModel.new odoPredictModel.odoNoiseModel.set(Math::exp( 0.05 ** 2 ), 0, Math::exp( 0.05 ** 2 ), 0 ) # # run # # predict with command u [v,w] u = Jmath::Vec.new(2) slamEkf.predict(odoPredictModel, u) # update # FIXME
Extra doc for macro can go here... (you can delete this section if not relevant)
The interface of the module is generated from the following files:
try
{ } catch
block for this module. Classes | |
class | jafar::slam::AbstractMapManager |
Abstract map manager. More... | |
class | jafar::slam::AbstractMapObject |
class Abstract Map Object More... | |
class | jafar::slam::BaseSlam |
Base class for Slam algorithms that can be used by managers. More... | |
class | jafar::slam::BasisFeatureModel |
A basis features includes the X,Y,Z coordinates of the origin, plus the raw, yaw and pitch angles. More... | |
class | jafar::slam::InitStateMember |
Initial state gaussian member (or hypothesis). More... | |
class | jafar::slam::InitFeature |
A generic bearing only feature. More... | |
class | jafar::slam::BearingOnlyFeatureObserveModel |
Bearing only feature observation model. More... | |
class | jafar::slam::InfFeatureObserveModel |
A feature at infinity observe model. More... | |
class | jafar::slam::TrajectoryPoseRecord |
A pose from the trajectory. More... | |
class | jafar::slam::BearingOnlySlam |
Bearing only slam. More... | |
class | jafar::slam::DalaManager |
Class for managing Dala. More... | |
class | jafar::slam::BaseFeature |
Generic feature. More... | |
class | jafar::slam::FeatureModel |
This class defines a generic feature model. More... | |
class | jafar::slam::BaseFeatureObserveModel |
The root class for all feature models. More... | |
class | jafar::slam::FeatureObserveModel |
Fully observable feature observe model. More... | |
class | jafar::slam::Full3dPredictModel |
Full 3d predict model. More... | |
class | jafar::slam::FreeStateCollector |
This class acts as a collector of free state in the SLAM. More... | |
class | jafar::slam::DefaultMapManager |
Default map manager. More... | |
class | jafar::slam::LocalMapManager |
Local slam manager. More... | |
class | jafar::slam::GlobalMapManager |
Global (long term) map manager. More... | |
class | jafar::slam::Observation |
Observation. More... | |
class | jafar::slam::OdoNoiseModel |
Odometry noise model. More... | |
class | jafar::slam::Odo3dPredictModel |
3d odometry predict model. More... | |
class | jafar::slam::PointFeatureModel |
Sizeless 3D point model. More... | |
class | jafar::slam::CartesianPointFeatureObserveModel |
sizeless point cartesian observe model. More... | |
class | jafar::slam::PolarPointFeatureObserveModel |
sizeless point polar observe model. More... | |
class | jafar::slam::BearingPointFeatureObserveModel |
sizeless point bearing-only observe model. More... | |
class | jafar::slam::ImagePointFeatureObserveModel |
sizeless point from perspective image observe model. More... | |
class | jafar::slam::StereoImagePointFeatureObserveModel |
sizeless point from stereo images observe model. More... | |
class | jafar::slam::OmniImagePointFeatureObserveModel |
sizeless point from omnidirectional image observe model. More... | |
class | jafar::slam::PointInfFeatureModel |
Sizeless 3D point at infinity model. More... | |
class | jafar::slam::BearingPointInfFeatureObserveModel |
Point at infinity bearing-only observe model. More... | |
class | jafar::slam::OmniImagePointInfFeatureObserveModel |
Point at infinity observed in a panoramique image. More... | |
class | jafar::slam::PointInvDepthFeatureModel |
Sizeless 3D point using the inverse-depth parametrisation. More... | |
class | jafar::slam::BearingPointInvDepthFeatureObserveModel |
Sizeless 3D point using the inverse-depth parametrisation, bearings-only sensor. More... | |
class | jafar::slam::OmniImagePointInvDepthFeatureObserveModel |
Sizeless 3D point using the inverse-depth parametrisation observed in a panoramic image. More... | |
class | jafar::slam::ImagePointInvDepthFeatureObserveModel |
Sizeless 3D point using the inverse-depth parametrisation observed in a perspective image. More... | |
class | jafar::slam::PoseCopy |
A special object of the map to estimate a local frame. More... | |
class | jafar::slam::BaseRobot |
Base robot model. More... | |
class | jafar::slam::SegmentAnchorFeature |
A plucker segment anchored feature, with its extremities. More... | |
class | jafar::slam::SegAnchorPluckerFeatureModel |
3D segments using anchored plucker parametrisation. More... | |
class | jafar::slam::ImageAnchorPluckerFeatureObserveModel |
3D segments using the anchored plucker parametrisation observed in a perspective image. More... | |
class | jafar::slam::SegmentObservation |
Observation of a segment. More... | |
class | jafar::slam::StereoSegmentObservation |
Observation of a segment. More... | |
class | jafar::slam::SegmentFeatureContraintModel |
Segment Feature constriant model. More... | |
class | jafar::slam::SegmentFeature |
A segment feature, with its extremities. More... | |
class | jafar::slam::SegmentFeatureModel |
segment model. More... | |
class | jafar::slam::ImageEuclideanPluckerFeatureObserveModel |
segment extracted from an image observe model. More... | |
class | jafar::slam::ImagePluckerFeatureObserveModel |
Sizeless 3D segment using the homogenous coordinates parametrisation observed in a perspective image. More... | |
class | jafar::slam::RhoThetaImagePluckerFeatureObserveModel |
Observation Model using Rho Theta parametrisation. More... | |
class | jafar::slam::ScaledHomogeneousImagePluckerFeatureObserveModel |
Observation Model using Scaled Homogeneous parametrisation. More... | |
class | jafar::slam::StereoImagePluckerFeatureObserveModel |
Observation Model using a Stereo head, two uvd points for init, two rho-thetas for updates. More... | |
class | jafar::slam::SegmentIDFeature |
A segment inverse depth feature, with its extremities. More... | |
class | jafar::slam::SegInvDepthFeatureModel |
3D segments using 2 points inverse-depth parametrisation. More... | |
class | jafar::slam::ImageSegInvDepthFeatureObserveModel |
Sizeless 3D point using the inverse-depth parametrisation observed in a perspective image. More... | |
class | jafar::slam::ImageSegInvDepthInovFeatureObserveModel |
Sizeless 3D point using the inverse-depth parametrisation observed in a perspective image. More... | |
class | jafar::slam::SlamEkf |
This class solves SLAM problem using the EKF-based academic solution. More... | |
class | jafar::slam::SlamEventListener |
Interface for Slam listeners. More... | |
class | jafar::slam::SlamEventAdapter |
Adapter for Slam listeners. More... | |
class | jafar::slam::BoSlamEventListener |
Interface for BoSlam listeners. More... | |
class | jafar::slam::BoSlamEventAdapter |
Adapter for BoSlam listeners. More... | |
class | jafar::slam::SlamException |
Base class for all exceptions defined in the module slam. More... | |
class | jafar::slamlines::ImageSegment |
class Image Segment More... | |
class | jafar::slamlines::ImageSegmentManager |
class Image Segment Manager More... | |
class | jafar::slamlines::ImageHomogenCoordSegmentManager |
Namespaces | |
namespace | jafar::slam::EulerTools |
Functions for operations related to Euler angles lines in SLAM. | |
namespace | jafar::slam::lineTools |
Functions for operations related to lines in SLAM (Plucker, homogeneous, rho-theta, and others) | |
Files | |
file | eulerTools.hpp |
Toolbox for operations related to Euler angles in SLAM. | |
file | lineTools.hpp |
Toolbox for operations related to lines in SLAM (Plucker, homogeneous, rho-theta, and others) | |
Functions | |
bool | jafar::slam::operator< (TrajectoryPoseRecord const &p1, TrajectoryPoseRecord const &p2) |
This operator compares TrajectoryPoseRecord. |
bool jafar::slam::operator< | ( | TrajectoryPoseRecord const & | p1, |
TrajectoryPoseRecord const & | p2 | ||
) |
This operator compares TrajectoryPoseRecord.
It is used to find the pose to throw away.
Generated on Wed Oct 15 2014 00:37:30 for Jafar by doxygen 1.7.6.1 |