Namespaces | |
namespace | msg |
namespace | srv |
Classes | |
struct | BarycenterDistancePredicate |
class | CloudCollector |
PCL filter that collects clouds. More... | |
class | CloudCollectorROS |
ROS wrapper for the pcl filter. More... | |
class | LaserMapper |
class | LaserSlamException |
A base class for all laser_slam exceptions; provides a handy boost::format parent constructor. More... | |
struct | LocalizedScan_ |
struct | Lock |
class | OdomConstraints |
Generates just odometric constraints between successive nodes. More... | |
class | OdomLocalizer |
Localization that just uses odometry. More... | |
class | OdomSlam |
Publishes odometry-based constraints and localization. More... | |
class | PointCloudSnapshotter |
Collects laser scans and transforms them into a point cloud w.r.t the base frame at a fixed point in time. Also publishes a 2d occupancy grid based on the scans. More... | |
struct | RecentScanTime |
struct | RecentScanTimeRequest_ |
struct | RecentScanTimeResponse_ |
class | ScanIntersection |
Construct with the dimensions of the scan polygon, and then repeatedly call unseenProportion. More... | |
class | ScanMatchConstraints |
Uses scan matching to generate sequential and loop closure constraints. More... | |
class | ScanMatchLocalizer |
Localization based on scan matching. More... | |
struct | ScanOrdering |
struct | SnapshotTransformException |
Typedefs | |
typedef std::vector< unsigned > | Chain |
typedef pose_graph::CachedNodeMap < sensor_msgs::PointCloud2 > | CloudMap |
typedef std::vector < msg::GraphConstraint > | ConstraintVec |
typedef ::laser_slam::LocalizedScan_ < std::allocator< void > > | LocalizedScan |
typedef boost::shared_ptr < ::laser_slam::LocalizedScan const > | LocalizedScanConstPtr |
typedef boost::shared_ptr < ::laser_slam::LocalizedScan > | LocalizedScanPtr |
typedef boost::mutex::scoped_lock | Lock |
typedef boost::shared_ptr < karto_scan_matcher::KartoScanMatcher > | MatcherPtr |
typedef boost::optional < gm::PoseStamped > | MaybeLoc |
typedef boost::optional< unsigned > | MaybeNode |
typedef boost::optional < ros::Time > | MaybeTime |
typedef std::map< unsigned, unsigned > | NodeMap |
typedef boost::optional< const msg::ConstraintGraphDiff & > | OptionalDiff |
typedef ::laser_slam::RecentScanTimeRequest_ < std::allocator< void > > | RecentScanTimeRequest |
typedef boost::shared_ptr < ::laser_slam::RecentScanTimeRequest const > | RecentScanTimeRequestConstPtr |
typedef boost::shared_ptr < ::laser_slam::RecentScanTimeRequest > | RecentScanTimeRequestPtr |
typedef ::laser_slam::RecentScanTimeResponse_ < std::allocator< void > > | RecentScanTimeResponse |
typedef boost::shared_ptr < ::laser_slam::RecentScanTimeResponse const > | RecentScanTimeResponseConstPtr |
typedef boost::shared_ptr < ::laser_slam::RecentScanTimeResponse > | RecentScanTimeResponsePtr |
typedef boost::circular_buffer < sm::LaserScan::ConstPtr > | ScanBuf |
typedef pose_graph::CachedNodeMap < laser_slam::LocalizedScan > | ScanMap |
typedef vector< btTransform > | Scans |
typedef std::vector < ksm::ScanWithPose > | ScanVec |
typedef boost::shared_ptr < tf::TransformListener > | TfPtr |
Functions | |
sm::PointCloud2::ConstPtr | generateGlobalCloud (const pg::ConstraintGraph &graph, const CloudMap &clouds, const string &global_frame) |
sensor_msgs::PointCloud2::ConstPtr | generateGlobalCloud (const pose_graph::ConstraintGraph &graph, const CloudMap &db, const std::string &global_frame) |
Generate a global cloud from a graph and saved node clouds. | |
nm::OccupancyGrid::ConstPtr | generateGlobalMap (const pg::ConstraintGraph &graph, const ScanMap &scans, const double resolution, const string &global_frame, const bool cleanup_grid, const pg::NodePoseMap &opt_poses_, const double robot_radius) |
nav_msgs::OccupancyGrid::ConstPtr | generateGlobalMap (const pose_graph::ConstraintGraph &graph, const ScanMap &db, const double resolution, const std::string &global_frame, bool cleanup_grid, const pose_graph::NodePoseMap &poses, const double robot_radius) |
Generate a global grid corresponding to graph. | |
nm::MapMetaData | getGridBounds (const pg::ConstraintGraph &graph, const double resolution) |
karto_scan_matcher::ScanMatchResult | globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pg::NodeSet &nodes, const ScanMap &scans, const sm::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution, const double min_x, const double min_y, const double max_x, const double max_y) |
karto_scan_matcher::ScanMatchResult | globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pg::NodeSet &nodes, const ScanMap &scans, const sm::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution) |
karto_scan_matcher::ScanMatchResult | globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution, double min_x, double min_y, double max_x, double max_y) |
Basically, do repeated local matches by discretizing the world using global_resolution. | |
karto_scan_matcher::ScanMatchResult | globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution) |
Basically, do repeated local matches by discretizing the world using global_resolution. | |
pg::NodeSet | largestComp (const pg::ConstraintGraph &g) |
ScanVec | makeRefScans (const pg::ConstraintGraph &g, const ScanMap &scans, const pg::NodeSet &nodes, const tf::Pose &laser_offset) |
ScanIntersection | makeScanInt () |
const std::string | NEXT_NODE_TOPIC ("scan_match_constraints_next_node") |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::laser_slam::LocalizedScan_< ContainerAllocator > &v) |
void | optimizeGraph (pg::ConstraintGraph *g, pg::NodePoseMap *poses, const pg::NodeSet &nodes, ros::ServiceClient &srv) |
double | pointToLineSegment (const btVector3 &p, const btVector3 &p1, const btVector3 &p2) |
const std::string | PREV_NODE_TOPIC ("scan_match_constraints_prev_node") |
ksm::ScanMatchResult | scanMatchNodes (const pg::ConstraintGraph &g, MatcherPtr matcher, const pg::NodeSet &nodes, const ScanMap &scans, const sm::LaserScan &scan, const tf::Pose &init_estimate, const tf::Pose &laser_offset) |
karto_scan_matcher::ScanMatchResult | scanMatchNodes (const pose_graph::ConstraintGraph &g, MatcherPtr matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &init_estimate, const tf::Pose &laser_offset) |
const ros::Duration | TRANSFORM_TOLERANCE (0.3) |
Variables | |
const double | DISTANCE_UPDATE_INC = 0.5 |
const double | EXPECTED_NODE_DISTANCE = 0.3 |
const double | GLOBAL_MATCH_MIN_RESPONSE = 0.6 |
const unsigned | LOCALIZATION_BUFFER_SIZE = 50 |
const double | LOOP_MATCH_FINE_MULTIPLIER = 0.2 |
const double | MAX_EXTRAPOLATION = 5.0 |
const double | MAX_SPEED = 1.0 |
const double | PADDING = 10.0 |
We'll create the grid with this much padding around the provided poses. | |
const double | POLL_INC = 0.1 |
const double | POLL_MAX = 1 |
const double | SCAN_BUFFER_SIZE = 100 |
const double | SCAN_TIME_INC = 0.2 |
const double | SCAN_TIMEOUT = 30.0 |
const double | SCAN_UPDATE_ANGLE_THRESHOLD = 0.5 |
const double | SCAN_UPDATE_DISTANCE_THRESHOLD = 1.0 |
typedef std::vector<unsigned> laser_slam::Chain |
Definition at line 58 of file scan_match_constraints.h.
typedef pose_graph::CachedNodeMap<sensor_msgs::PointCloud2> laser_slam::CloudMap |
Definition at line 52 of file global_map.h.
typedef std::vector<msg::GraphConstraint> laser_slam::ConstraintVec |
Definition at line 59 of file scan_match_constraints.h.
typedef ::laser_slam::LocalizedScan_<std::allocator<void> > laser_slam::LocalizedScan |
Definition at line 261 of file LocalizedScan.h.
typedef boost::shared_ptr< ::laser_slam::LocalizedScan const> laser_slam::LocalizedScanConstPtr |
Definition at line 264 of file LocalizedScan.h.
typedef boost::shared_ptr< ::laser_slam::LocalizedScan> laser_slam::LocalizedScanPtr |
Definition at line 263 of file LocalizedScan.h.
typedef boost::mutex::scoped_lock laser_slam::Lock |
Definition at line 45 of file odom_constraints.cpp.
typedef boost::shared_ptr<karto_scan_matcher::KartoScanMatcher> laser_slam::MatcherPtr |
Definition at line 47 of file scan_matching.h.
typedef boost::optional<gm::PoseStamped> laser_slam::MaybeLoc |
Definition at line 61 of file laser_slam_node.cpp.
typedef boost::optional<unsigned> laser_slam::MaybeNode |
Definition at line 53 of file scan_match_constraints.cpp.
typedef boost::optional< ros::Time > laser_slam::MaybeTime |
Definition at line 60 of file laser_slam_node.cpp.
typedef std::map<unsigned, unsigned> laser_slam::NodeMap |
Definition at line 52 of file scan_match_constraints.cpp.
typedef optional< const msg::ConstraintGraphDiff & > laser_slam::OptionalDiff |
typedef ::laser_slam::RecentScanTimeRequest_<std::allocator<void> > laser_slam::RecentScanTimeRequest |
Definition at line 102 of file RecentScanTime.h.
typedef boost::shared_ptr< ::laser_slam::RecentScanTimeRequest const> laser_slam::RecentScanTimeRequestConstPtr |
Definition at line 105 of file RecentScanTime.h.
typedef boost::shared_ptr< ::laser_slam::RecentScanTimeRequest> laser_slam::RecentScanTimeRequestPtr |
Definition at line 104 of file RecentScanTime.h.
typedef ::laser_slam::RecentScanTimeResponse_<std::allocator<void> > laser_slam::RecentScanTimeResponse |
Definition at line 190 of file RecentScanTime.h.
typedef boost::shared_ptr< ::laser_slam::RecentScanTimeResponse const> laser_slam::RecentScanTimeResponseConstPtr |
Definition at line 193 of file RecentScanTime.h.
typedef boost::shared_ptr< ::laser_slam::RecentScanTimeResponse> laser_slam::RecentScanTimeResponsePtr |
Definition at line 192 of file RecentScanTime.h.
typedef boost::circular_buffer<sm::LaserScan::ConstPtr> laser_slam::ScanBuf |
Definition at line 49 of file point_cloud_snapshotter.cpp.
typedef pose_graph::CachedNodeMap< LocalizedScan > laser_slam::ScanMap |
Definition at line 51 of file global_map.h.
typedef vector<btTransform> laser_slam::Scans |
Definition at line 49 of file scan_intersection.cpp.
typedef std::vector<ksm::ScanWithPose> laser_slam::ScanVec |
Definition at line 57 of file scan_matching.cpp.
typedef boost::shared_ptr<tf::TransformListener> laser_slam::TfPtr |
sm::PointCloud2::ConstPtr laser_slam::generateGlobalCloud | ( | const pg::ConstraintGraph & | graph, | |
const CloudMap & | clouds, | |||
const string & | global_frame | |||
) |
Definition at line 173 of file global_map.cpp.
sensor_msgs::PointCloud2::ConstPtr laser_slam::generateGlobalCloud | ( | const pose_graph::ConstraintGraph & | graph, | |
const CloudMap & | db, | |||
const std::string & | global_frame | |||
) |
Generate a global cloud from a graph and saved node clouds.
nm::OccupancyGrid::ConstPtr laser_slam::generateGlobalMap | ( | const pg::ConstraintGraph & | graph, | |
const ScanMap & | scans, | |||
const double | resolution, | |||
const string & | global_frame, | |||
const bool | cleanup_grid, | |||
const pg::NodePoseMap & | opt_poses_, | |||
const double | robot_radius | |||
) |
Definition at line 91 of file global_map.cpp.
nav_msgs::OccupancyGrid::ConstPtr laser_slam::generateGlobalMap | ( | const pose_graph::ConstraintGraph & | graph, | |
const ScanMap & | db, | |||
const double | resolution, | |||
const std::string & | global_frame, | |||
bool | cleanup_grid, | |||
const pose_graph::NodePoseMap & | poses, | |||
const double | robot_radius | |||
) |
Generate a global grid corresponding to graph.
nm::MapMetaData laser_slam::getGridBounds | ( | const pg::ConstraintGraph & | graph, | |
const double | resolution | |||
) |
Definition at line 56 of file global_map.cpp.
karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization | ( | const pose_graph::ConstraintGraph & | g, | |
MatcherPtr | local_matcher, | |||
const pg::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sm::LaserScan & | scan, | |||
const tf::Pose & | laser_offset, | |||
double | global_resolution, | |||
double | angular_resolution, | |||
const double | min_x, | |||
const double | min_y, | |||
const double | max_x, | |||
const double | max_y | |||
) |
Definition at line 131 of file scan_matching.cpp.
karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization | ( | const pose_graph::ConstraintGraph & | g, | |
MatcherPtr | local_matcher, | |||
const pg::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sm::LaserScan & | scan, | |||
const tf::Pose & | laser_offset, | |||
double | global_resolution, | |||
double | angular_resolution | |||
) |
Definition at line 100 of file scan_matching.cpp.
karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization | ( | const pose_graph::ConstraintGraph & | g, | |
MatcherPtr | local_matcher, | |||
const pose_graph::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sensor_msgs::LaserScan & | scan, | |||
const tf::Pose & | laser_offset, | |||
double | global_resolution, | |||
double | angular_resolution, | |||
double | min_x, | |||
double | min_y, | |||
double | max_x, | |||
double | max_y | |||
) |
Basically, do repeated local matches by discretizing the world using global_resolution.
karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization | ( | const pose_graph::ConstraintGraph & | g, | |
MatcherPtr | local_matcher, | |||
const pose_graph::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sensor_msgs::LaserScan & | scan, | |||
const tf::Pose & | laser_offset, | |||
double | global_resolution, | |||
double | angular_resolution | |||
) |
Basically, do repeated local matches by discretizing the world using global_resolution.
pg::NodeSet laser_slam::largestComp | ( | const pg::ConstraintGraph & | g | ) |
ScanVec laser_slam::makeRefScans | ( | const pg::ConstraintGraph & | g, | |
const ScanMap & | scans, | |||
const pg::NodeSet & | nodes, | |||
const tf::Pose & | laser_offset | |||
) |
Definition at line 59 of file scan_matching.cpp.
ScanIntersection laser_slam::makeScanInt | ( | ) |
Definition at line 90 of file laser_slam_node.cpp.
const std::string laser_slam::NEXT_NODE_TOPIC | ( | "scan_match_constraints_next_node" | ) |
std::ostream& laser_slam::operator<< | ( | std::ostream & | s, | |
const ::laser_slam::LocalizedScan_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 268 of file LocalizedScan.h.
void laser_slam::optimizeGraph | ( | pg::ConstraintGraph * | g, | |
pg::NodePoseMap * | poses, | |||
const pg::NodeSet & | nodes, | |||
ros::ServiceClient & | srv | |||
) |
double laser_slam::pointToLineSegment | ( | const btVector3 & | p, | |
const btVector3 & | p1, | |||
const btVector3 & | p2 | |||
) | [inline] |
Definition at line 52 of file scan_intersection.cpp.
const std::string laser_slam::PREV_NODE_TOPIC | ( | "scan_match_constraints_prev_node" | ) |
ksm::ScanMatchResult laser_slam::scanMatchNodes | ( | const pg::ConstraintGraph & | g, | |
MatcherPtr | matcher, | |||
const pg::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sm::LaserScan & | scan, | |||
const tf::Pose & | init_estimate, | |||
const tf::Pose & | laser_offset | |||
) |
Definition at line 86 of file scan_matching.cpp.
karto_scan_matcher::ScanMatchResult laser_slam::scanMatchNodes | ( | const pose_graph::ConstraintGraph & | g, | |
MatcherPtr | matcher, | |||
const pose_graph::NodeSet & | nodes, | |||
const ScanMap & | scans, | |||
const sensor_msgs::LaserScan & | scan, | |||
const tf::Pose & | init_estimate, | |||
const tf::Pose & | laser_offset | |||
) |
const ros::Duration laser_slam::TRANSFORM_TOLERANCE | ( | 0. | 3 | ) |
const double laser_slam::DISTANCE_UPDATE_INC = 0.5 |
Definition at line 61 of file scan_match_constraints.cpp.
const double laser_slam::EXPECTED_NODE_DISTANCE = 0.3 |
Definition at line 60 of file scan_match_constraints.cpp.
const double laser_slam::GLOBAL_MATCH_MIN_RESPONSE = 0.6 |
Definition at line 138 of file scan_match_localization.h.
const unsigned laser_slam::LOCALIZATION_BUFFER_SIZE = 50 |
Definition at line 55 of file scan_match_constraints.cpp.
const double laser_slam::LOOP_MATCH_FINE_MULTIPLIER = 0.2 |
Definition at line 56 of file scan_match_constraints.cpp.
const double laser_slam::MAX_EXTRAPOLATION = 5.0 |
Definition at line 59 of file scan_match_constraints.cpp.
const double laser_slam::MAX_SPEED = 1.0 |
Definition at line 62 of file scan_match_constraints.cpp.
const double laser_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 laser_slam::POLL_INC = 0.1 |
Definition at line 57 of file scan_match_constraints.cpp.
const double laser_slam::POLL_MAX = 1 |
Definition at line 58 of file scan_match_constraints.cpp.
const double laser_slam::SCAN_BUFFER_SIZE = 100 |
Definition at line 131 of file point_cloud_snapshotter.h.
const double laser_slam::SCAN_TIME_INC = 0.2 |
Definition at line 63 of file laser_slam_node.cpp.
const double laser_slam::SCAN_TIMEOUT = 30.0 |
Definition at line 51 of file point_cloud_snapshotter.cpp.
const double laser_slam::SCAN_UPDATE_ANGLE_THRESHOLD = 0.5 |
Definition at line 53 of file point_cloud_snapshotter.cpp.
const double laser_slam::SCAN_UPDATE_DISTANCE_THRESHOLD = 1.0 |
Definition at line 52 of file point_cloud_snapshotter.cpp.