| Public Member Functions | |
| Costmap3DOFNode () | |
| Protected Member Functions | |
| void | cbMap (const nav_msgs::OccupancyGrid::ConstPtr &msg, const costmap_cspace::Costmap3dLayerBase::Ptr map) | 
| void | cbMapOverlay (const nav_msgs::OccupancyGrid::ConstPtr &msg, const costmap_cspace::Costmap3dLayerBase::Ptr map) | 
| void | cbPublishFootprint (const ros::TimerEvent &event, const geometry_msgs::PolygonStamped msg) | 
| bool | cbUpdate (const costmap_cspace::CSpace3DMsg::Ptr &map, const costmap_cspace_msgs::CSpace3DUpdate::Ptr &update) | 
| bool | cbUpdateStatic (const costmap_cspace::CSpace3DMsg::Ptr &map) | 
| void | publishDebug (const costmap_cspace_msgs::CSpace3D &map) | 
| Static Protected Member Functions | |
| static costmap_cspace::MapOverlayMode | getMapOverlayModeFromString (const std::string overlay_mode_str) | 
| Protected Attributes | |
| costmap_cspace::Costmap3d::Ptr | costmap_ | 
| std::vector< std::pair< nav_msgs::OccupancyGrid::ConstPtr, costmap_cspace::Costmap3dLayerBase::Ptr > > | map_buffer_ | 
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | pnh_ | 
| ros::Publisher | pub_costmap_ | 
| ros::Publisher | pub_costmap_update_ | 
| ros::Publisher | pub_debug_ | 
| ros::Publisher | pub_footprint_ | 
| ros::Subscriber | sub_map_ | 
| std::vector< ros::Subscriber > | sub_map_overlay_ | 
| ros::Timer | timer_footprint_ | 
Definition at line 45 of file costmap_3d.cpp.
| 
 | inline | 
Definition at line 180 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 64 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 86 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 157 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 112 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 105 of file costmap_3d.cpp.
| 
 | inlinestaticprotected | 
Definition at line 164 of file costmap_3d.cpp.
| 
 | inlineprotected | 
Definition at line 133 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 58 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 62 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 48 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 49 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 52 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 53 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 55 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 54 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 50 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 51 of file costmap_3d.cpp.
| 
 | protected | 
Definition at line 56 of file costmap_3d.cpp.