Public Member Functions | Private Attributes
pr2_navigation_controllers::GoalPasser Class Reference

#include <goal_passer.h>

Inheritance diagram for pr2_navigation_controllers::GoalPasser:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 GoalPasser ()
void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)

Private Attributes

costmap_2d::Costmap2DROScostmap_ros_
geometry_msgs::PoseStamped last_goal_

Detailed Description

Definition at line 44 of file goal_passer.h.


Constructor & Destructor Documentation

Definition at line 46 of file goal_passer.h.


Member Function Documentation

void pr2_navigation_controllers::GoalPasser::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Implements nav_core::BaseGlobalPlanner.

Definition at line 44 of file goal_passer.cpp.

bool pr2_navigation_controllers::GoalPasser::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
) [virtual]

Implements nav_core::BaseGlobalPlanner.

Definition at line 49 of file goal_passer.cpp.


Member Data Documentation

Definition at line 51 of file goal_passer.h.

geometry_msgs::PoseStamped pr2_navigation_controllers::GoalPasser::last_goal_ [private]

Definition at line 52 of file goal_passer.h.


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


pr2_navigation_controllers
Author(s): Ported by Adam Leeper, originally by Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 12:43:53