laser_slam::PointCloudSnapshotter Class Reference

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...

#include <point_cloud_snapshotter.h>

List of all members.

Public Member Functions

 PointCloudSnapshotter (boost::shared_ptr< tf::TransformListener > tf, ros::NodeHandle param_nh)
boost::optional< ros::Time > recentScanTime (const ros::Time &t1, const ros::Time &t2) const

Private Member Functions

void diffCallback (boost::optional< const graph_mapping_msgs::ConstraintGraphDiff & > diff, const pose_graph::ConstraintGraph &graph)
tf::Pose ffPoseAt (const ros::Time &t)
void locCallback (graph_mapping_msgs::LocalizationDistribution::ConstPtr m)
void processAndSaveScan (sensor_msgs::LaserScan::ConstPtr scan, const geometry_msgs::PoseStamped &pos)
void processAndSaveScan (sensor_msgs::LaserScan::ConstPtr scan, const ros::Time &t, const unsigned n)
laser_slam::LocalizedScan::Ptr processScan (sensor_msgs::LaserScan::ConstPtr scan, const geometry_msgs::Pose &sensor_pose) const
void publishMap (const ros::TimerEvent &e)
bool recentScanTimeCallback (RecentScanTime::Request &req, RecentScanTime::Response &resp)
void scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan)
void storeOptPoses (graph_mapping_msgs::NodePoses::ConstPtr m)

Private Attributes

const std::string base_frame_
const bool cleanup_grid_
warehouse::WarehouseClient db_
pose_graph::DiffSubscriber diff_sub_
const
pose_graph::CachedNodeMap
< geometry_msgs::Pose > 
ff_poses_
const std::string fixed_frame_
ros::ServiceClient get_poses_client_
const std::string global_frame_
const double grid_resolution_
ros::Subscriber laser_sub_
boost::optional
< geometry_msgs::PoseStamped > 
last_loc_
ros::Subscriber loc_sub_
ros::Publisher map_pub_
ros::Timer map_pub_timer_
boost::mutex mutex_
ros::NodeHandle nh_
pose_graph::NodePoseMap opt_poses_
bool optimize_flag_
ros::NodeHandle param_nh_
ros::ServiceServer recent_scan_time_server_
boost::circular_buffer
< sensor_msgs::LaserScan::ConstPtr > 
recent_scans_
boost::optional< unsigned > ref_node_
const double robot_radius_
const ros::Duration scan_save_min_gap_
const double scan_time_tol_
pose_graph::CachedNodeMap
< laser_slam::LocalizedScan
scans_
const std::string sensor_frame_
geometry_msgs::Pose sensor_pose_
boost::shared_ptr
< tf::TransformListener > 
tf_
const ros::Duration transform_wait_duration_

Detailed Description

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.

Definition at line 56 of file point_cloud_snapshotter.h.


Constructor & Destructor Documentation

laser_slam::PointCloudSnapshotter::PointCloudSnapshotter ( boost::shared_ptr< tf::TransformListener >  tf,
ros::NodeHandle  param_nh 
)

Definition at line 57 of file point_cloud_snapshotter.cpp.


Member Function Documentation

void laser_slam::PointCloudSnapshotter::diffCallback ( boost::optional< const graph_mapping_msgs::ConstraintGraphDiff & >  diff,
const pose_graph::ConstraintGraph &  graph 
) [private]
tf::Pose laser_slam::PointCloudSnapshotter::ffPoseAt ( const ros::Time &  t  )  [private]

Definition at line 221 of file point_cloud_snapshotter.cpp.

void laser_slam::PointCloudSnapshotter::locCallback ( graph_mapping_msgs::LocalizationDistribution::ConstPtr  m  )  [private]
void laser_slam::PointCloudSnapshotter::processAndSaveScan ( sensor_msgs::LaserScan::ConstPtr  scan,
const geometry_msgs::PoseStamped &  pos 
) [private]
void laser_slam::PointCloudSnapshotter::processAndSaveScan ( sensor_msgs::LaserScan::ConstPtr  scan,
const ros::Time &  t,
const unsigned  n 
) [private]
laser_slam::LocalizedScan::Ptr laser_slam::PointCloudSnapshotter::processScan ( sensor_msgs::LaserScan::ConstPtr  scan,
const geometry_msgs::Pose &  sensor_pose 
) const [private]
void laser_slam::PointCloudSnapshotter::publishMap ( const ros::TimerEvent &  e  )  [private]

Definition at line 343 of file point_cloud_snapshotter.cpp.

MaybeTime laser_slam::PointCloudSnapshotter::recentScanTime ( const ros::Time &  t1,
const ros::Time &  t2 
) const
Returns:
A time between t1 and t2 corresponding to a recent scan, or uninitialized if no such scan exists
Precondition:
t2 >= t1

Definition at line 102 of file point_cloud_snapshotter.cpp.

bool laser_slam::PointCloudSnapshotter::recentScanTimeCallback ( RecentScanTime::Request req,
RecentScanTime::Response resp 
) [private]

Definition at line 121 of file point_cloud_snapshotter.cpp.

void laser_slam::PointCloudSnapshotter::scanCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan  )  [private]
void laser_slam::PointCloudSnapshotter::storeOptPoses ( graph_mapping_msgs::NodePoses::ConstPtr  m  )  [private]

Member Data Documentation

Definition at line 85 of file point_cloud_snapshotter.h.

Definition at line 91 of file point_cloud_snapshotter.h.

warehouse::WarehouseClient laser_slam::PointCloudSnapshotter::db_ [private]

Definition at line 114 of file point_cloud_snapshotter.h.

pose_graph::DiffSubscriber laser_slam::PointCloudSnapshotter::diff_sub_ [private]

Definition at line 118 of file point_cloud_snapshotter.h.

const pose_graph::CachedNodeMap<geometry_msgs::Pose> laser_slam::PointCloudSnapshotter::ff_poses_ [private]

Definition at line 116 of file point_cloud_snapshotter.h.

Definition at line 85 of file point_cloud_snapshotter.h.

Definition at line 120 of file point_cloud_snapshotter.h.

Definition at line 85 of file point_cloud_snapshotter.h.

Definition at line 87 of file point_cloud_snapshotter.h.

Definition at line 117 of file point_cloud_snapshotter.h.

boost::optional<geometry_msgs::PoseStamped> laser_slam::PointCloudSnapshotter::last_loc_ [private]

Definition at line 100 of file point_cloud_snapshotter.h.

Definition at line 117 of file point_cloud_snapshotter.h.

Definition at line 119 of file point_cloud_snapshotter.h.

Definition at line 121 of file point_cloud_snapshotter.h.

boost::mutex laser_slam::PointCloudSnapshotter::mutex_ [mutable, private]

Definition at line 111 of file point_cloud_snapshotter.h.

ros::NodeHandle laser_slam::PointCloudSnapshotter::nh_ [private]

Definition at line 112 of file point_cloud_snapshotter.h.

pose_graph::NodePoseMap laser_slam::PointCloudSnapshotter::opt_poses_ [private]

Definition at line 98 of file point_cloud_snapshotter.h.

Definition at line 105 of file point_cloud_snapshotter.h.

Definition at line 84 of file point_cloud_snapshotter.h.

Definition at line 122 of file point_cloud_snapshotter.h.

boost::circular_buffer<sensor_msgs::LaserScan::ConstPtr> laser_slam::PointCloudSnapshotter::recent_scans_ [private]

Definition at line 99 of file point_cloud_snapshotter.h.

boost::optional<unsigned> laser_slam::PointCloudSnapshotter::ref_node_ [private]

Definition at line 103 of file point_cloud_snapshotter.h.

Definition at line 92 of file point_cloud_snapshotter.h.

Definition at line 88 of file point_cloud_snapshotter.h.

Definition at line 90 of file point_cloud_snapshotter.h.

Definition at line 115 of file point_cloud_snapshotter.h.

Definition at line 85 of file point_cloud_snapshotter.h.

geometry_msgs::Pose laser_slam::PointCloudSnapshotter::sensor_pose_ [private]

Definition at line 89 of file point_cloud_snapshotter.h.

boost::shared_ptr<tf::TransformListener> laser_slam::PointCloudSnapshotter::tf_ [private]

Definition at line 113 of file point_cloud_snapshotter.h.

Definition at line 86 of file point_cloud_snapshotter.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


laser_slam
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:53:31 2013