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, const costmap_cspace_msgs::CSpace3DUpdate::Ptr update) |
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.
Costmap3DOFNode::Costmap3DOFNode | ( | ) | [inline] |
Definition at line 167 of file costmap_3d.cpp.
void Costmap3DOFNode::cbMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg, |
const costmap_cspace::Costmap3dLayerBase::Ptr | map | ||
) | [inline, protected] |
Definition at line 63 of file costmap_3d.cpp.
void Costmap3DOFNode::cbMapOverlay | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg, |
const costmap_cspace::Costmap3dLayerBase::Ptr | map | ||
) | [inline, protected] |
Definition at line 85 of file costmap_3d.cpp.
void Costmap3DOFNode::cbPublishFootprint | ( | const ros::TimerEvent & | event, |
const geometry_msgs::PolygonStamped | msg | ||
) | [inline, protected] |
Definition at line 144 of file costmap_3d.cpp.
bool Costmap3DOFNode::cbUpdate | ( | const costmap_cspace::CSpace3DMsg::Ptr | map, |
const costmap_cspace_msgs::CSpace3DUpdate::Ptr | update | ||
) | [inline, protected] |
Definition at line 112 of file costmap_3d.cpp.
bool Costmap3DOFNode::cbUpdateStatic | ( | const costmap_cspace::CSpace3DMsg::Ptr | map, |
const costmap_cspace_msgs::CSpace3DUpdate::Ptr | update | ||
) | [inline, protected] |
Definition at line 104 of file costmap_3d.cpp.
static costmap_cspace::MapOverlayMode Costmap3DOFNode::getMapOverlayModeFromString | ( | const std::string | overlay_mode_str | ) | [inline, static, protected] |
Definition at line 151 of file costmap_3d.cpp.
void Costmap3DOFNode::publishDebug | ( | const costmap_cspace_msgs::CSpace3D & | map | ) | [inline, protected] |
Definition at line 120 of file costmap_3d.cpp.
costmap_cspace::Costmap3d::Ptr Costmap3DOFNode::costmap_ [protected] |
Definition at line 58 of file costmap_3d.cpp.
std::vector< std::pair<nav_msgs::OccupancyGrid::ConstPtr, costmap_cspace::Costmap3dLayerBase::Ptr> > Costmap3DOFNode::map_buffer_ [protected] |
Definition at line 61 of file costmap_3d.cpp.
ros::NodeHandle Costmap3DOFNode::nh_ [protected] |
Definition at line 48 of file costmap_3d.cpp.
ros::NodeHandle Costmap3DOFNode::pnh_ [protected] |
Definition at line 49 of file costmap_3d.cpp.
ros::Publisher Costmap3DOFNode::pub_costmap_ [protected] |
Definition at line 52 of file costmap_3d.cpp.
ros::Publisher Costmap3DOFNode::pub_costmap_update_ [protected] |
Definition at line 53 of file costmap_3d.cpp.
ros::Publisher Costmap3DOFNode::pub_debug_ [protected] |
Definition at line 55 of file costmap_3d.cpp.
ros::Publisher Costmap3DOFNode::pub_footprint_ [protected] |
Definition at line 54 of file costmap_3d.cpp.
ros::Subscriber Costmap3DOFNode::sub_map_ [protected] |
Definition at line 50 of file costmap_3d.cpp.
std::vector<ros::Subscriber> Costmap3DOFNode::sub_map_overlay_ [protected] |
Definition at line 51 of file costmap_3d.cpp.
ros::Timer Costmap3DOFNode::timer_footprint_ [protected] |
Definition at line 56 of file costmap_3d.cpp.