Public Member Functions | Private Member Functions | Private Attributes
graph_slam::GraphMapper Class Reference

List of all members.

Public Member Functions

 GraphMapper ()
 Constructor initializes node based on ros params, then sets up the various timers and callbacks, then returns.

Private Member Functions

void addNewNode ()
PoseStamped currentFixedFramePose () const
bool generateMap (GenerateGlobalMap::Request &req, GenerateGlobalMap::Response &resp)
optional< NodeIdgetGridNode (const NodeId n) const
void initializeFromFile (const string &fname)
void optimizePoses ()
void optimizePosesTimed (const WallTimerEvent &e)
void publishLocalization (const WallTimerEvent &e)
bool saveGraph (SaveGraph::Request &req, SaveGraph::Response &resp)
void scanCallback (const sm::LaserScan::ConstPtr &scan)
void setupConstraintGenerators ()
void statusCheck (const WallTimerEvent &e)
bool sufficientlyFarApart (const Pose &p1, const Pose &p2) const
void updateConstraintLocalizations ()
void updateFixedFramePose (const Time &t)
void updateGraph (const WallTimerEvent &e)
void updateGrid ()
void visualize (const WallTimerEvent &e)
void visualizeGridCallback (const UInt64 &n)

Private Attributes

const double angle_threshold_
const string base_frame_
vector< ConstraintGenPtrconstraint_generators_
ros::Publisher current_frame_pub_
unsigned current_graph_id_
optional< NodeIdcurrent_grid_node_
DiffPublisher diff_pub_
std::queue< PoseGraphDiff > diffs_
const string fixed_frame_
ros::ServiceServer generate_map_srv_
PoseGraph graph_
ros::WallTimer graph_publication_timer_
ros::ServiceServer graph_save_srv_
map< NodeId, NodeSetgrid_node_to_nodes_
bool initialized_
optional< PoseStamped > last_fixed_frame_pose_
optional< NodeIdlast_node_
LaserPtr last_scan_
ros::Publisher local_grid_pub_
const double local_grid_resolution_
const double local_grid_size_
optional< LocalizationStatelocalization_
boost::shared_ptr
< ScanMatchLocalization
localizer_
ros::Publisher marker_array_pub_
boost::mutex mutex_
NodeHandle nh_
NodePoseMap node_fixed_frame_poses_
map< NodeId, NodeIdnode_to_grid_node_
optional< NodeIdnode_to_visualize_
ros::WallTimer optimization_timer_
const bool optimize_
NodePoseMap optimized_node_poses_
const double pos_threshold_
ros::Subscriber scan_sub_
const string sensor_frame_
ros::WallTimer status_check_timer_
tf::TransformListener tf_
tf::TransformBroadcaster tf_broadcaster_
ros::WallTimer update_timer_
const bool use_spa_3d_
ros::Publisher vis_marker_pub_
ros::Publisher vis_scan_pub_
ros::WallTimer visualization_timer_
ros::Subscriber visualize_grid_sub_

Detailed Description

Definition at line 124 of file graph_mapper.cpp.


Constructor & Destructor Documentation

Constructor initializes node based on ros params, then sets up the various timers and callbacks, then returns.

Definition at line 399 of file graph_mapper.cpp.


Member Function Documentation

Definition at line 618 of file graph_mapper.cpp.

PoseStamped graph_slam::GraphMapper::currentFixedFramePose ( ) const [private]
bool graph_slam::GraphMapper::generateMap ( GenerateGlobalMap::Request &  req,
GenerateGlobalMap::Response &  resp 
) [private]

Definition at line 493 of file graph_mapper.cpp.

optional< NodeId > graph_slam::GraphMapper::getGridNode ( const NodeId  n) const [private]

Definition at line 885 of file graph_mapper.cpp.

void graph_slam::GraphMapper::initializeFromFile ( const string &  fname) [private]

Definition at line 344 of file graph_mapper.cpp.

Definition at line 754 of file graph_mapper.cpp.

Definition at line 746 of file graph_mapper.cpp.

Definition at line 911 of file graph_mapper.cpp.

bool graph_slam::GraphMapper::saveGraph ( SaveGraph::Request &  req,
SaveGraph::Response &  resp 
) [private]

Definition at line 478 of file graph_mapper.cpp.

void graph_slam::GraphMapper::scanCallback ( const sm::LaserScan::ConstPtr &  scan) [private]

Definition at line 464 of file graph_mapper.cpp.

Definition at line 322 of file graph_mapper.cpp.

Definition at line 968 of file graph_mapper.cpp.

bool graph_slam::GraphMapper::sufficientlyFarApart ( const Pose p1,
const Pose p2 
) const [private]

Definition at line 609 of file graph_mapper.cpp.

Definition at line 373 of file graph_mapper.cpp.

void graph_slam::GraphMapper::updateFixedFramePose ( const Time t) [private]
Todo:
this can technically throw a tf exception if the last few lines take > 10 seconds to execute

Definition at line 578 of file graph_mapper.cpp.

Definition at line 525 of file graph_mapper.cpp.

Definition at line 725 of file graph_mapper.cpp.

void graph_slam::GraphMapper::visualize ( const WallTimerEvent e) [private]

Definition at line 795 of file graph_mapper.cpp.

void graph_slam::GraphMapper::visualizeGridCallback ( const UInt64 &  n) [private]

Definition at line 473 of file graph_mapper.cpp.


Member Data Documentation

Definition at line 213 of file graph_mapper.cpp.

const string graph_slam::GraphMapper::base_frame_ [private]

Definition at line 204 of file graph_mapper.cpp.

Definition at line 287 of file graph_mapper.cpp.

Definition at line 284 of file graph_mapper.cpp.

Definition at line 272 of file graph_mapper.cpp.

Definition at line 260 of file graph_mapper.cpp.

Definition at line 289 of file graph_mapper.cpp.

std::queue<PoseGraphDiff> graph_slam::GraphMapper::diffs_ [private]

Definition at line 266 of file graph_mapper.cpp.

const string graph_slam::GraphMapper::fixed_frame_ [private]

Definition at line 207 of file graph_mapper.cpp.

Definition at line 285 of file graph_mapper.cpp.

Definition at line 247 of file graph_mapper.cpp.

Definition at line 281 of file graph_mapper.cpp.

Definition at line 285 of file graph_mapper.cpp.

Definition at line 257 of file graph_mapper.cpp.

Definition at line 232 of file graph_mapper.cpp.

optional<PoseStamped> graph_slam::GraphMapper::last_fixed_frame_pose_ [private]

Definition at line 238 of file graph_mapper.cpp.

Definition at line 244 of file graph_mapper.cpp.

Definition at line 235 of file graph_mapper.cpp.

Definition at line 284 of file graph_mapper.cpp.

Definition at line 225 of file graph_mapper.cpp.

Definition at line 222 of file graph_mapper.cpp.

Definition at line 263 of file graph_mapper.cpp.

Definition at line 288 of file graph_mapper.cpp.

Definition at line 284 of file graph_mapper.cpp.

boost::mutex graph_slam::GraphMapper::mutex_ [mutable, private]

Definition at line 278 of file graph_mapper.cpp.

Definition at line 279 of file graph_mapper.cpp.

Definition at line 241 of file graph_mapper.cpp.

Definition at line 254 of file graph_mapper.cpp.

Definition at line 269 of file graph_mapper.cpp.

Definition at line 281 of file graph_mapper.cpp.

const bool graph_slam::GraphMapper::optimize_ [private]

Definition at line 216 of file graph_mapper.cpp.

Definition at line 251 of file graph_mapper.cpp.

Definition at line 210 of file graph_mapper.cpp.

Definition at line 283 of file graph_mapper.cpp.

Definition at line 201 of file graph_mapper.cpp.

Definition at line 281 of file graph_mapper.cpp.

Definition at line 280 of file graph_mapper.cpp.

Definition at line 286 of file graph_mapper.cpp.

Definition at line 281 of file graph_mapper.cpp.

Definition at line 219 of file graph_mapper.cpp.

Definition at line 284 of file graph_mapper.cpp.

Definition at line 284 of file graph_mapper.cpp.

Definition at line 281 of file graph_mapper.cpp.

Definition at line 283 of file graph_mapper.cpp.


The documentation for this class was generated from the following file:


graph_slam
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:21