Public Member Functions | Private Member Functions | Private Attributes
MultiMapper Class Reference

#include <MultiMapper.h>

List of all members.

Public Member Functions

bool getMap (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
 MultiMapper ()
void onMessage (const void *sender, karto::MapperEventArguments &args)
void publishLoop ()
void publishTransform ()
void receiveInitialPose (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &pose)
void receiveLaserScan (const sensor_msgs::LaserScan::ConstPtr &scan)
void receiveLocalizedScan (const nav2d_msgs::LocalizedScan::ConstPtr &scan)
void sendLocalizedScan (const sensor_msgs::LaserScan::ConstPtr &scan, const karto::Pose2 &pose)
void setScanSolver (karto::ScanSolver *scanSolver)
 ~MultiMapper ()

Private Member Functions

karto::LocalizedRangeScancreateFromRosMessage (const sensor_msgs::LaserScan &scan, const karto::Identifier &robot)
bool sendMap ()
void setRobotPose (double x, double y, double yaw)
bool updateMap ()

Private Attributes

ros::Publisher mEdgesPublisher
nav_msgs::OccupancyGrid mGridMap
ros::Subscriber mInitialPoseSubscriber
karto::LaserRangeFinderPtr mLaser
std::string mLaserFrame
ros::Subscriber mLaserSubscriber
std::string mLaserTopic
ros::WallTime mLastMapUpdate
bool mMapChanged
std::string mMapFrame
karto::SmartPointer
< karto::OpenMapper
mMapper
ros::Publisher mMapPublisher
double mMapResolution
ros::ServiceServer mMapServer
std::string mMapService
tf::Transform mMapToOdometry
std::string mMapTopic
int mMapUpdateRate
double mMaxCovariance
int mMinMapSize
int mNodesAdded
std::string mOdometryFrame
tf::Transform mOdometryOffset
std::string mOffsetFrame
std::map< int,
karto::LaserRangeFinderPtr
mOtherLasers
ros::Publisher mOtherRobotsPublisher
ros::Publisher mPosePublisher
bool mPublishPoseGraph
double mRangeThreshold
std::string mRobotFrame
int mRobotID
std::string mScanInputTopic
std::string mScanOutputTopic
ros::Publisher mScanPublisher
ros::Subscriber mScanSubscriber
SelfLocalizermSelfLocalizer
int mState
tf::TransformBroadcaster mTransformBroadcaster
tf::TransformListener mTransformListener
ros::Publisher mVerticesPublisher

Detailed Description

Definition at line 23 of file MultiMapper.h.


Constructor & Destructor Documentation

Definition at line 9 of file MultiMapper.cpp.

Definition at line 176 of file MultiMapper.cpp.


Member Function Documentation

karto::LocalizedRangeScan * MultiMapper::createFromRosMessage ( const sensor_msgs::LaserScan &  scan,
const karto::Identifier robot 
) [private]

Definition at line 223 of file MultiMapper.cpp.

bool MultiMapper::getMap ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
)

Definition at line 391 of file MultiMapper.cpp.

void MultiMapper::onMessage ( const void *  sender,
karto::MapperEventArguments args 
)

Definition at line 681 of file MultiMapper.cpp.

Definition at line 686 of file MultiMapper.cpp.

void MultiMapper::receiveInitialPose ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  pose)

Definition at line 664 of file MultiMapper.cpp.

void MultiMapper::receiveLaserScan ( const sensor_msgs::LaserScan::ConstPtr &  scan)

Definition at line 259 of file MultiMapper.cpp.

void MultiMapper::receiveLocalizedScan ( const nav2d_msgs::LocalizedScan::ConstPtr &  scan)

Definition at line 544 of file MultiMapper.cpp.

void MultiMapper::sendLocalizedScan ( const sensor_msgs::LaserScan::ConstPtr &  scan,
const karto::Pose2 pose 
)

Definition at line 636 of file MultiMapper.cpp.

bool MultiMapper::sendMap ( ) [private]

Definition at line 410 of file MultiMapper.cpp.

void MultiMapper::setRobotPose ( double  x,
double  y,
double  yaw 
) [private]

Definition at line 186 of file MultiMapper.cpp.

Definition at line 181 of file MultiMapper.cpp.

bool MultiMapper::updateMap ( ) [private]

Definition at line 481 of file MultiMapper.cpp.


Member Data Documentation

Definition at line 63 of file MultiMapper.h.

nav_msgs::OccupancyGrid MultiMapper::mGridMap [private]

Definition at line 57 of file MultiMapper.h.

Definition at line 68 of file MultiMapper.h.

Definition at line 71 of file MultiMapper.h.

std::string MultiMapper::mLaserFrame [private]

Definition at line 89 of file MultiMapper.h.

Definition at line 66 of file MultiMapper.h.

std::string MultiMapper::mLaserTopic [private]

Definition at line 94 of file MultiMapper.h.

Definition at line 86 of file MultiMapper.h.

bool MultiMapper::mMapChanged [private]

Definition at line 74 of file MultiMapper.h.

std::string MultiMapper::mMapFrame [private]

Definition at line 93 of file MultiMapper.h.

Definition at line 72 of file MultiMapper.h.

Definition at line 60 of file MultiMapper.h.

double MultiMapper::mMapResolution [private]

Definition at line 78 of file MultiMapper.h.

Definition at line 59 of file MultiMapper.h.

std::string MultiMapper::mMapService [private]

Definition at line 96 of file MultiMapper.h.

Definition at line 54 of file MultiMapper.h.

std::string MultiMapper::mMapTopic [private]

Definition at line 95 of file MultiMapper.h.

Definition at line 82 of file MultiMapper.h.

double MultiMapper::mMaxCovariance [private]

Definition at line 80 of file MultiMapper.h.

int MultiMapper::mMinMapSize [private]

Definition at line 85 of file MultiMapper.h.

int MultiMapper::mNodesAdded [private]

Definition at line 84 of file MultiMapper.h.

std::string MultiMapper::mOdometryFrame [private]

Definition at line 91 of file MultiMapper.h.

Definition at line 55 of file MultiMapper.h.

std::string MultiMapper::mOffsetFrame [private]

Definition at line 92 of file MultiMapper.h.

Definition at line 73 of file MultiMapper.h.

Definition at line 65 of file MultiMapper.h.

Definition at line 64 of file MultiMapper.h.

Definition at line 83 of file MultiMapper.h.

double MultiMapper::mRangeThreshold [private]

Definition at line 79 of file MultiMapper.h.

std::string MultiMapper::mRobotFrame [private]

Definition at line 90 of file MultiMapper.h.

int MultiMapper::mRobotID [private]

Definition at line 77 of file MultiMapper.h.

std::string MultiMapper::mScanInputTopic [private]

Definition at line 97 of file MultiMapper.h.

std::string MultiMapper::mScanOutputTopic [private]

Definition at line 98 of file MultiMapper.h.

Definition at line 61 of file MultiMapper.h.

Definition at line 67 of file MultiMapper.h.

Definition at line 49 of file MultiMapper.h.

int MultiMapper::mState [private]

Definition at line 81 of file MultiMapper.h.

Definition at line 53 of file MultiMapper.h.

Definition at line 52 of file MultiMapper.h.

Definition at line 62 of file MultiMapper.h.


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


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Sun Apr 2 2017 03:53:09