Public Member Functions | Public Attributes | Protected Attributes
cob_3d_mapping::GeometryMapNode Class Reference

Ros node for GeometryMap. More...

#include <geometry_map_node.h>

List of all members.

Public Member Functions

bool clearMap (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 Service callback for clearing the map.
void dynReconfCallback (cob_3d_mapping_geometry_map::geometry_map_nodeConfig &config, uint32_t level)
 callback for dynamic reconfigure
 GeometryMapNode ()
 Constructor.
bool getMap (cob_3d_mapping_msgs::GetGeometryMap::Request &req, cob_3d_mapping_msgs::GetGeometryMap::Response &res)
 Service callback for getting the map.
bool modifyMap (cob_3d_mapping_msgs::ModifyMap::Request &req, cob_3d_mapping_msgs::ModifyMap::Response &res)
 service callback for modifying the map.
void publishMap ()
 Map arrays are published.
bool setMap (cob_3d_mapping_msgs::SetGeometryMap::Request &req, cob_3d_mapping_msgs::SetGeometryMap::Response &res)
 Service callback for setting the map.
void shapeCallback (const cob_3d_mapping_msgs::ShapeArray::ConstPtr &sa)
 Callback for incoming shapes.
 ~GeometryMapNode ()

Public Attributes

ros::NodeHandle n_
 Cylinder primitives are published.

Protected Attributes

ros::ServiceServer clear_map_server_
 The server for clearing the map.
dynamic_reconfigure::Server
< cob_3d_mapping_geometry_map::geometry_map_nodeConfig > 
config_server_
 Dynamic Reconfigure server.
bool enable_cyl_
 If true , processing of cylinders is activated.
bool enable_poly_
 If true , processing of polygons is activated.
GeometryMap geometry_map_
 Map containing geometrys (polygons,cylinders)
ros::ServiceServer get_map_server_
 The server for getting the map.
std::string map_frame_id_
 Name of target frame.
ros::Publisher map_pub_
 Publish Map array as shape message.
ros::ServiceServer modify_map_server_
 The server for modifying the map.
ros::ServiceServer set_map_server_
 The server for setting the map.
ros::Subscriber shape_sub_
 Subscription to shape message to be processed.

Detailed Description

Ros node for GeometryMap.

Definition at line 88 of file geometry_map_node.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 77 of file geometry_map_node.cpp.

brief Destructor

Definition at line 99 of file geometry_map_node.h.


Member Function Documentation

bool GeometryMapNode::clearMap ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
)

Service callback for clearing the map.

Deletes 3d map of the environment.

Parameters:
reqThe service request.
resThe service response.
Returns:
True, if clearing was successful.

Definition at line 147 of file geometry_map_node.cpp.

void GeometryMapNode::dynReconfCallback ( cob_3d_mapping_geometry_map::geometry_map_nodeConfig &  config,
uint32_t  level 
)

callback for dynamic reconfigure

everytime the dynamic reconfiguration changes this function will be called

Parameters:
configdata of configuration
levelbit descriptor which notifies which parameter changed
Returns:
nothing

Definition at line 90 of file geometry_map_node.cpp.

bool GeometryMapNode::getMap ( cob_3d_mapping_msgs::GetGeometryMap::Request &  req,
cob_3d_mapping_msgs::GetGeometryMap::Response &  res 
)

Service callback for getting the map.

Fills the service response of the GetGeometricMap service with the current map

Parameters:
reqThe service request.
resThe service response.
Returns:
True, if getting was successful.

Definition at line 159 of file geometry_map_node.cpp.

bool GeometryMapNode::modifyMap ( cob_3d_mapping_msgs::ModifyMap::Request &  req,
cob_3d_mapping_msgs::ModifyMap::Response &  res 
)

service callback for modifying the map.

Modifies the map with the shapes in the service request, returns the modified map in the response.

Parameters:
reqThe service request.
resThe service response.
Returns:
True, if modifying was successful.

Definition at line 218 of file geometry_map_node.cpp.

Map arrays are published.

Shape message is generated and published to specified topic.

Definition at line 267 of file geometry_map_node.cpp.

bool GeometryMapNode::setMap ( cob_3d_mapping_msgs::SetGeometryMap::Request &  req,
cob_3d_mapping_msgs::SetGeometryMap::Response &  res 
)

Service callback for setting the map.

Sets the map with the service request.

Parameters:
reqThe service request.
resThe service response.
Returns:
True, if setting was successful.

Definition at line 188 of file geometry_map_node.cpp.

void GeometryMapNode::shapeCallback ( const cob_3d_mapping_msgs::ShapeArray::ConstPtr &  sa)

Callback for incoming shapes.

Parameters:
saThe incoming shape array.
Returns:
nothing

Definition at line 103 of file geometry_map_node.cpp.


Member Data Documentation

The server for clearing the map.

Definition at line 220 of file geometry_map_node.h.

dynamic_reconfigure::Server<cob_3d_mapping_geometry_map::geometry_map_nodeConfig> cob_3d_mapping::GeometryMapNode::config_server_ [protected]

Dynamic Reconfigure server.

The dynamic reconfigure server.

Definition at line 231 of file geometry_map_node.h.

If true , processing of cylinders is activated.

Definition at line 225 of file geometry_map_node.h.

If true , processing of polygons is activated.

Definition at line 226 of file geometry_map_node.h.

Map containing geometrys (polygons,cylinders)

Definition at line 233 of file geometry_map_node.h.

The server for getting the map.

Definition at line 221 of file geometry_map_node.h.

Name of target frame.

Definition at line 234 of file geometry_map_node.h.

Publish Map array as shape message.

Definition at line 219 of file geometry_map_node.h.

The server for modifying the map.

Definition at line 223 of file geometry_map_node.h.

Cylinder primitives are published.

Visualization markers of Cylinder shapes are created and published. Polygon marker is filled out.

Note:
Method is not yet implemented.
Parameters:
[in]pPolygon, whose marker is to be filled.
[in]mCorresponding marker.
[out]m_tFilled marker. ShapeCluster marker is filled out.
Note:
Method is not yet implemented.
Parameters:
[in]pCylinder, whose marker is to be filled.
[in]mCorresponding marker.
[out]m_tFilled marker. ShapeCluster marker is filled out.
Note:
Method is not yet implemented.
Parameters:
[in]pShapeCluster, whose marker is to be filled.
[in]mCorresponding marker.
[out]m_tFilled marker. ROS node handle.

Definition at line 215 of file geometry_map_node.h.

The server for setting the map.

Definition at line 222 of file geometry_map_node.h.

Subscription to shape message to be processed.

Definition at line 218 of file geometry_map_node.h.


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


cob_3d_mapping_geometry_map
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:21