#include <MultiMapper.h>
Definition at line 23 of file MultiMapper.h.
Definition at line 10 of file MultiMapper.cpp.
Definition at line 177 of file MultiMapper.cpp.
bool MultiMapper::getMap | ( | nav_msgs::GetMap::Request & | req, |
nav_msgs::GetMap::Response & | res | ||
) |
Definition at line 368 of file MultiMapper.cpp.
void MultiMapper::onMessage | ( | const void * | sender, |
karto::MapperEventArguments & | args | ||
) |
Definition at line 671 of file MultiMapper.cpp.
void MultiMapper::publishLoop | ( | ) |
void MultiMapper::publishTransform | ( | ) |
Definition at line 676 of file MultiMapper.cpp.
void MultiMapper::receiveInitialPose | ( | const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & | pose | ) |
Definition at line 654 of file MultiMapper.cpp.
void MultiMapper::receiveLaserScan | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) |
Definition at line 224 of file MultiMapper.cpp.
void MultiMapper::receiveLocalizedScan | ( | const nav2d_msgs::LocalizedScan::ConstPtr & | scan | ) |
Definition at line 521 of file MultiMapper.cpp.
void MultiMapper::sendLocalizedScan | ( | const sensor_msgs::LaserScan::ConstPtr & | scan, |
const karto::Pose2 & | pose | ||
) |
Definition at line 626 of file MultiMapper.cpp.
bool MultiMapper::sendMap | ( | ) | [private] |
Definition at line 387 of file MultiMapper.cpp.
void MultiMapper::setRobotPose | ( | double | x, |
double | y, | ||
double | yaw | ||
) | [private] |
Definition at line 187 of file MultiMapper.cpp.
void MultiMapper::setScanSolver | ( | karto::ScanSolver * | scanSolver | ) |
Definition at line 182 of file MultiMapper.cpp.
bool MultiMapper::updateMap | ( | ) | [private] |
Definition at line 458 of file MultiMapper.cpp.
ros::Publisher MultiMapper::mEdgesPublisher [private] |
Definition at line 62 of file MultiMapper.h.
nav_msgs::OccupancyGrid MultiMapper::mGridMap [private] |
Definition at line 56 of file MultiMapper.h.
Definition at line 67 of file MultiMapper.h.
Definition at line 70 of file MultiMapper.h.
std::string MultiMapper::mLaserFrame [private] |
Definition at line 88 of file MultiMapper.h.
ros::Subscriber MultiMapper::mLaserSubscriber [private] |
Definition at line 65 of file MultiMapper.h.
std::string MultiMapper::mLaserTopic [private] |
Definition at line 93 of file MultiMapper.h.
ros::WallTime MultiMapper::mLastMapUpdate [private] |
Definition at line 85 of file MultiMapper.h.
bool MultiMapper::mMapChanged [private] |
Definition at line 73 of file MultiMapper.h.
std::string MultiMapper::mMapFrame [private] |
Definition at line 92 of file MultiMapper.h.
Definition at line 71 of file MultiMapper.h.
ros::Publisher MultiMapper::mMapPublisher [private] |
Definition at line 59 of file MultiMapper.h.
double MultiMapper::mMapResolution [private] |
Definition at line 77 of file MultiMapper.h.
ros::ServiceServer MultiMapper::mMapServer [private] |
Definition at line 58 of file MultiMapper.h.
std::string MultiMapper::mMapService [private] |
Definition at line 95 of file MultiMapper.h.
tf::Transform MultiMapper::mMapToOdometry [private] |
Definition at line 53 of file MultiMapper.h.
std::string MultiMapper::mMapTopic [private] |
Definition at line 94 of file MultiMapper.h.
int MultiMapper::mMapUpdateRate [private] |
Definition at line 81 of file MultiMapper.h.
double MultiMapper::mMaxCovariance [private] |
Definition at line 79 of file MultiMapper.h.
int MultiMapper::mMinMapSize [private] |
Definition at line 84 of file MultiMapper.h.
int MultiMapper::mNodesAdded [private] |
Definition at line 83 of file MultiMapper.h.
std::string MultiMapper::mOdometryFrame [private] |
Definition at line 90 of file MultiMapper.h.
tf::Transform MultiMapper::mOdometryOffset [private] |
Definition at line 54 of file MultiMapper.h.
std::string MultiMapper::mOffsetFrame [private] |
Definition at line 91 of file MultiMapper.h.
std::map<int, karto::LaserRangeFinderPtr> MultiMapper::mOtherLasers [private] |
Definition at line 72 of file MultiMapper.h.
Definition at line 64 of file MultiMapper.h.
ros::Publisher MultiMapper::mPosePublisher [private] |
Definition at line 63 of file MultiMapper.h.
bool MultiMapper::mPublishPoseGraph [private] |
Definition at line 82 of file MultiMapper.h.
double MultiMapper::mRangeThreshold [private] |
Definition at line 78 of file MultiMapper.h.
std::string MultiMapper::mRobotFrame [private] |
Definition at line 89 of file MultiMapper.h.
int MultiMapper::mRobotID [private] |
Definition at line 76 of file MultiMapper.h.
std::string MultiMapper::mScanInputTopic [private] |
Definition at line 96 of file MultiMapper.h.
std::string MultiMapper::mScanOutputTopic [private] |
Definition at line 97 of file MultiMapper.h.
ros::Publisher MultiMapper::mScanPublisher [private] |
Definition at line 60 of file MultiMapper.h.
ros::Subscriber MultiMapper::mScanSubscriber [private] |
Definition at line 66 of file MultiMapper.h.
SelfLocalizer* MultiMapper::mSelfLocalizer [private] |
Definition at line 48 of file MultiMapper.h.
int MultiMapper::mState [private] |
Definition at line 80 of file MultiMapper.h.
Definition at line 52 of file MultiMapper.h.
Definition at line 51 of file MultiMapper.h.
Definition at line 61 of file MultiMapper.h.