Classes | |
class | ConstraintGenerator |
class | DiffPublisher |
class | DiffSubscriber |
class | FakeLoopClosureGenerator |
class | GraphMapper |
class | KartoLaserConstraints |
struct | LocalizationState |
class | LoopScanMatcher |
struct | NodeConstraint |
class | OdomConstraintGenerator |
Constraint generator that generates a single constraint to the previous node. More... | |
class | ScanManager |
Internally used class that contains sequential scan matching logic When using the ops, you have to instantiate a WithOptimizedPoses RAII object in a containing scope to set the optimized poses before doing anything else. More... | |
class | ScanMatchLocalization |
class | SequentialScanMatcher |
struct | WithOptimizedPoses |
RAII object for making ScanManager use a given set of optimized poses. More... | |
Typedefs | |
typedef std::vector< pg::NodeId > | Chain |
typedef std::vector< Chain > | ChainVec |
typedef boost::shared_ptr < ConstraintGenerator > | ConstraintGenPtr |
typedef boost::shared_ptr < nm::OccupancyGrid const > | GridConstPtr |
typedef boost::shared_ptr < nm::OccupancyGrid > | GridPtr |
typedef boost::shared_ptr < karto_scan_matcher::KartoScanMatcher > | KartoMatcherPtr |
typedef sensor_msgs::LaserScan::ConstPtr | LaserPtr |
typedef NodeSequenceMap::left_map::const_iterator | LeftIter |
typedef boost::mutex::scoped_lock | Lock |
typedef boost::shared_ptr < LoopScanMatcher > | LoopMatcherPtr |
typedef std::vector < NodeConstraint, Eigen3::aligned_allocator < NodeConstraint > > | NodeConstraintVector |
typedef std::map< pg::NodeId, geometry_msgs::Pose > | NodePoseMap |
typedef std::map< pg::NodeId, LaserPtr > | NodeScanMap |
typedef boost::bimap < pg::NodeId, pg::NodeId > | NodeSequenceMap |
typedef std::set< pg::NodeId > | NodeSet |
typedef NodeSequenceMap::right_map::const_iterator | RightIter |
typedef boost::shared_ptr < SequentialScanMatcher > | SeqMatcherPtr |
typedef NodeSequenceMap::value_type | SequenceLink |
Functions | |
void | addChain (const Chain &chain, ChainVec *chains, NodeSet *processed) |
void | addChain (const Chain &chain, vector< Chain > *chains, NodeSet *processed) |
void | addTransformedPoints (LocalizedCloud::ConstPtr cloud, const Pose &pose, sm::PointCloud *cloud_out) |
bool | alreadyHaveConstraintToTarget (const NodeConstraint &constraint, const NodeConstraintVector &constraints) |
Pose | applyConstraint (const Pose &p, const PoseConstraint &c) |
bool | closerTo (const gm::Pose2D &pose, const NodePoseMap &optimized_poses, const NodeId n1, const NodeId n2) |
ConstraintGenPtr | createConstraintGenerator (const ros::NodeHandle &nh) |
nav_msgs::OccupancyGrid::Ptr | generateGlobalMap (const pose_graph::PoseGraph &graph, const pose_graph::NodePoseMap &opt_poses, const double resolution) |
nm::MapMetaData | getGridBounds (const pg::NodePoseMap &poses, const double resolution) |
gm::Pose2D | getLaserOffset (const tf::TransformListener &tf, const sm::LaserScan &scan) |
double | getLocalizationRate () |
unsigned | getLocalizationsPerScanMatch () |
pg::PrecisionMatrix | getPrecisionMatrix (const karto_scan_matcher::ScanMatchResult &res, const bool use_covariances) |
Utility functions for subclasses. | |
template<class T > | |
T | getPrivateParam (const ros::NodeHandle &nh, const string &name, const T &default_val) |
template<class T > | |
T | getPrivateParam (const string &name, const T &default_val) |
unsigned | getUniqueId () |
ksm::ScanWithPose | makeScanWithPose (const NodePoseMap &optimized_poses, const NodeScanMap scans_, const NodeId n) |
template<typename Map > | |
Chain | onewayChain (const Map &m, const pg::NodeId seed, const NodeSet &allowed, const NodeSet &forbidden) |
bool | targetIs (const NodeConstraint &constraint, const NodeId n) |
void | TransformEigenToTF (const Eigen3::Affine3d &k, tf::Transform &t) |
bool | withinDistance (const PoseGraph &g, const NodeId n1, const NodeId n2, const double d) |
Variables | |
const double | DEFAULT_ANGLE_THRESHOLD = 1.57 |
const double | DEFAULT_POS_THRESHOLD = 2.0 |
const double | LOCALIZATION_RECENCY_THRESHOLD = 1.0 |
const double | PADDING = 10.0 |
We'll create the grid with this much padding around the provided poses. | |
const double | RADIAN_TO_METER_MULT = 1.0 |
const double | STATUS_CHECK_INT = 5.0 |
typedef std::vector<pg::NodeId> graph_slam::Chain |
Definition at line 56 of file scan_manager.h.
typedef vector< Chain > graph_slam::ChainVec |
Definition at line 61 of file scan_manager.h.
typedef boost::shared_ptr<ConstraintGenerator> graph_slam::ConstraintGenPtr |
Definition at line 102 of file constraint_generator.h.
typedef boost::shared_ptr<nm::OccupancyGrid const> graph_slam::GridConstPtr |
Definition at line 110 of file graph_mapper.cpp.
typedef boost::shared_ptr<nm::OccupancyGrid> graph_slam::GridPtr |
Definition at line 109 of file graph_mapper.cpp.
typedef boost::shared_ptr<karto_scan_matcher::KartoScanMatcher> graph_slam::KartoMatcherPtr |
Definition at line 57 of file scan_manager.h.
typedef sensor_msgs::LaserScan::ConstPtr graph_slam::LaserPtr |
Definition at line 58 of file scan_manager.h.
typedef NodeSequenceMap::left_map::const_iterator graph_slam::LeftIter |
Definition at line 58 of file scan_manager.cpp.
typedef boost::mutex::scoped_lock graph_slam::Lock |
Definition at line 107 of file graph_mapper.cpp.
typedef boost::shared_ptr<LoopScanMatcher> graph_slam::LoopMatcherPtr |
Definition at line 55 of file karto_laser_constraints.h.
typedef std::vector<NodeConstraint, Eigen3::aligned_allocator<NodeConstraint> > graph_slam::NodeConstraintVector |
Definition at line 78 of file constraint_generator.h.
typedef std::map<pg::NodeId, geometry_msgs::Pose> graph_slam::NodePoseMap |
Definition at line 79 of file constraint_generator.h.
typedef std::map<pg::NodeId, LaserPtr> graph_slam::NodeScanMap |
Definition at line 59 of file scan_manager.h.
typedef boost::bimap<pg::NodeId, pg::NodeId> graph_slam::NodeSequenceMap |
Definition at line 55 of file scan_manager.h.
typedef set< NodeId > graph_slam::NodeSet |
Definition at line 60 of file scan_manager.h.
typedef NodeSequenceMap::right_map::const_iterator graph_slam::RightIter |
Definition at line 59 of file scan_manager.cpp.
typedef boost::shared_ptr<SequentialScanMatcher> graph_slam::SeqMatcherPtr |
Definition at line 54 of file karto_laser_constraints.h.
typedef NodeSequenceMap::value_type graph_slam::SequenceLink |
Definition at line 57 of file scan_manager.cpp.
void graph_slam::addChain | ( | const Chain & | chain, |
ChainVec * | chains, | ||
NodeSet * | processed | ||
) |
void graph_slam::addChain | ( | const Chain & | chain, |
vector< Chain > * | chains, | ||
NodeSet * | processed | ||
) |
Definition at line 264 of file scan_manager.cpp.
void graph_slam::addTransformedPoints | ( | LocalizedCloud::ConstPtr | cloud, |
const Pose & | pose, | ||
sm::PointCloud * | cloud_out | ||
) |
Definition at line 783 of file graph_mapper.cpp.
bool graph_slam::alreadyHaveConstraintToTarget | ( | const NodeConstraint & | constraint, |
const NodeConstraintVector & | constraints | ||
) |
Definition at line 59 of file sequential_scan_matcher.cpp.
Pose graph_slam::applyConstraint | ( | const Pose & | p, |
const PoseConstraint & | c | ||
) |
Definition at line 775 of file graph_mapper.cpp.
bool graph_slam::closerTo | ( | const gm::Pose2D & | pose, |
const NodePoseMap & | optimized_poses, | ||
const NodeId | n1, | ||
const NodeId | n2 | ||
) |
Definition at line 192 of file scan_manager.cpp.
Definition at line 66 of file constraint_generator.cpp.
nm::OccupancyGrid::Ptr graph_slam::generateGlobalMap | ( | const pose_graph::PoseGraph & | graph, |
const pose_graph::NodePoseMap & | opt_poses, | ||
const double | resolution | ||
) |
Definition at line 79 of file global_map.cpp.
nm::MapMetaData graph_slam::getGridBounds | ( | const pg::NodePoseMap & | poses, |
const double | resolution | ||
) |
Definition at line 47 of file global_map.cpp.
gm::Pose2D graph_slam::getLaserOffset | ( | const tf::TransformListener & | tf, |
const sm::LaserScan & | scan | ||
) |
Definition at line 85 of file karto_laser_constraint_generator.cpp.
double graph_slam::getLocalizationRate | ( | ) |
Definition at line 384 of file graph_mapper.cpp.
unsigned graph_slam::getLocalizationsPerScanMatch | ( | ) |
Definition at line 389 of file graph_mapper.cpp.
PrecisionMatrix graph_slam::getPrecisionMatrix | ( | const karto_scan_matcher::ScanMatchResult & | res, |
const bool | use_covariances | ||
) |
Utility functions for subclasses.
Definition at line 252 of file scan_manager.cpp.
T graph_slam::getPrivateParam | ( | const ros::NodeHandle & | nh, |
const string & | name, | ||
const T & | default_val | ||
) |
Definition at line 56 of file constraint_generator.cpp.
T graph_slam::getPrivateParam | ( | const string & | name, |
const T & | default_val | ||
) |
Definition at line 311 of file graph_mapper.cpp.
unsigned graph_slam::getUniqueId | ( | ) |
Definition at line 299 of file graph_mapper.cpp.
ksm::ScanWithPose graph_slam::makeScanWithPose | ( | const NodePoseMap & | optimized_poses, |
const NodeScanMap | scans_, | ||
const NodeId | n | ||
) |
Definition at line 93 of file scan_manager.cpp.
Chain graph_slam::onewayChain | ( | const Map & | m, |
const pg::NodeId | seed, | ||
const NodeSet & | allowed, | ||
const NodeSet & | forbidden | ||
) |
Definition at line 169 of file scan_manager.h.
bool graph_slam::targetIs | ( | const NodeConstraint & | constraint, |
const NodeId | n | ||
) |
Definition at line 79 of file karto_laser_constraint_generator.cpp.
void graph_slam::TransformEigenToTF | ( | const Eigen3::Affine3d & | k, |
tf::Transform & | t | ||
) |
Definition at line 905 of file graph_mapper.cpp.
bool graph_slam::withinDistance | ( | const PoseGraph & | g, |
const NodeId | n1, | ||
const NodeId | n2, | ||
const double | d | ||
) |
Definition at line 718 of file graph_mapper.cpp.
const double graph_slam::DEFAULT_ANGLE_THRESHOLD = 1.57 |
Definition at line 117 of file graph_mapper.cpp.
const double graph_slam::DEFAULT_POS_THRESHOLD = 2.0 |
Definition at line 116 of file graph_mapper.cpp.
const double graph_slam::LOCALIZATION_RECENCY_THRESHOLD = 1.0 |
Definition at line 48 of file fake_loop_closure.h.
const double graph_slam::PADDING = 10.0 |
We'll create the grid with this much padding around the provided poses.
Definition at line 49 of file global_map.h.
const double graph_slam::RADIAN_TO_METER_MULT = 1.0 |
Definition at line 61 of file scan_manager.cpp.
const double graph_slam::STATUS_CHECK_INT = 5.0 |
Definition at line 118 of file graph_mapper.cpp.