Public Member Functions | Public Attributes | Protected Attributes | Private Types
PointMapNodelet Class Reference
Inheritance diagram for PointMapNodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool clearMap (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 action callback
void downsampleMap ()
 downsamples the map
void dynReconfCallback (cob_3d_mapping_point_map::point_map_nodeletConfig &config, uint32_t level)
 Callback for dynamic reconfigure server.
bool getMap (cob_3d_mapping_msgs::GetPointMap::Request &req, cob_3d_mapping_msgs::GetPointMap::Response &res)
 service callback for GetPointMap service
void onInit ()
 initializes parameters
 PointMapNodelet ()
bool setMap (cob_3d_mapping_msgs::SetPointMap::Request &req, cob_3d_mapping_msgs::SetPointMap::Response &res)
 sets reference map
void updateCallback (const pcl::PointCloud< Point >::Ptr &pc)
 callback for point cloud subroutine
void updateMap (const pcl::PointCloud< Point >::Ptr &pc)
 ~PointMapNodelet ()

Public Attributes

ros::NodeHandle n_

Protected Attributes

ros::ServiceServer clear_map_server_
boost::shared_ptr
< dynamic_reconfigure::Server
< cob_3d_mapping_point_map::point_map_nodeletConfig > > 
config_server_
unsigned int ctr_
std::string file_path_
ros::ServiceServer get_map_server_
bool is_running_
pcl::PointCloud< Pointmap_
std::string map_frame_id_
ros::Publisher map_pub_
ros::Subscriber point_cloud_sub_
bool save_
ros::ServiceServer set_map_server_
double voxel_leafsize_

Private Types

typedef pcl::PointXYZRGB Point

Detailed Description

Definition at line 102 of file point_map_nodelet.cpp.


Member Typedef Documentation

typedef pcl::PointXYZRGB PointMapNodelet::Point [private]

Definition at line 104 of file point_map_nodelet.cpp.


Constructor & Destructor Documentation

Definition at line 108 of file point_map_nodelet.cpp.

Definition at line 119 of file point_map_nodelet.cpp.


Member Function Documentation

bool PointMapNodelet::clearMap ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

action callback

default action callback to start or stop node

Parameters:
goalsettings
Returns:
nothing clears map

deletes 3d map of the environment

Parameters:
reqnot needed
resnot needed
Returns:
nothing

Definition at line 265 of file point_map_nodelet.cpp.

void PointMapNodelet::downsampleMap ( ) [inline]

downsamples the map

downsamples the map using the voxel_leafsize parameters to voxelize

Returns:
nothing

Definition at line 326 of file point_map_nodelet.cpp.

void PointMapNodelet::dynReconfCallback ( cob_3d_mapping_point_map::point_map_nodeletConfig &  config,
uint32_t  level 
) [inline]

Callback for dynamic reconfigure server.

Callback for dynamic reconfigure server

Returns:
nothing

Definition at line 132 of file point_map_nodelet.cpp.

bool PointMapNodelet::getMap ( cob_3d_mapping_msgs::GetPointMap::Request &  req,
cob_3d_mapping_msgs::GetPointMap::Response &  res 
) [inline]

service callback for GetPointMap service

Fills the service response of the GetPointMap service with the current point map

Parameters:
reqrequest to send map
resthe current point map
Returns:
nothing

Definition at line 288 of file point_map_nodelet.cpp.

void PointMapNodelet::onInit ( ) [inline, virtual]

initializes parameters

initializes parameters

Returns:
nothing

Implements nodelet::Nodelet.

Definition at line 150 of file point_map_nodelet.cpp.

bool PointMapNodelet::setMap ( cob_3d_mapping_msgs::SetPointMap::Request &  req,
cob_3d_mapping_msgs::SetPointMap::Response &  res 
) [inline]

sets reference map

sets the 3d map representing a static environment, overrides any existing map

Parameters:
reqcontaining reference map
resnot needed
Returns:
nothing

Definition at line 307 of file point_map_nodelet.cpp.

void PointMapNodelet::updateCallback ( const pcl::PointCloud< Point >::Ptr &  pc) [inline]

callback for point cloud subroutine

callback for keyframe subroutine which loads in the first step the unexact transformation from the laser sensors and calibrates the input cloud from the 3d camera. This already transformed data will be used to build a 3d map either aligned to the first frame or to an existing map. Additionally debug output to *.pcd files are possible.

Parameters:
reqnot used
resnot used
Returns:
nothing

Definition at line 183 of file point_map_nodelet.cpp.

void PointMapNodelet::updateMap ( const pcl::PointCloud< Point >::Ptr &  pc) [inline]

Definition at line 213 of file point_map_nodelet.cpp.


Member Data Documentation

Definition at line 341 of file point_map_nodelet.cpp.

boost::shared_ptr<dynamic_reconfigure::Server<cob_3d_mapping_point_map::point_map_nodeletConfig> > PointMapNodelet::config_server_ [protected]

Definition at line 345 of file point_map_nodelet.cpp.

unsigned int PointMapNodelet::ctr_ [protected]

Definition at line 347 of file point_map_nodelet.cpp.

std::string PointMapNodelet::file_path_ [protected]

Definition at line 351 of file point_map_nodelet.cpp.

Definition at line 342 of file point_map_nodelet.cpp.

bool PointMapNodelet::is_running_ [protected]

Definition at line 348 of file point_map_nodelet.cpp.

Definition at line 356 of file point_map_nodelet.cpp.

std::string PointMapNodelet::map_frame_id_ [protected]

Definition at line 353 of file point_map_nodelet.cpp.

Definition at line 340 of file point_map_nodelet.cpp.

Definition at line 335 of file point_map_nodelet.cpp.

Definition at line 339 of file point_map_nodelet.cpp.

bool PointMapNodelet::save_ [protected]

Definition at line 352 of file point_map_nodelet.cpp.

Definition at line 343 of file point_map_nodelet.cpp.

Definition at line 354 of file point_map_nodelet.cpp.


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


cob_3d_mapping_point_map
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:48