
| Public Types | |
| typedef actionlib::ActionServerBase< GetPathAction > | ActionServerBase | 
| typedef actionlib::ServerGoalHandle< GetPathAction > | GoalHandle | 
|  Public Types inherited from actionlib::ActionServerBase< GetPathAction > | |
| typedef ServerGoalHandle< GetPathAction > | GoalHandle | 
| Public Member Functions | |
| virtual void | initialize () | 
| MOCK_METHOD2 (publishResult, void(const actionlib_msgs::GoalStatus &, const Result &)) | |
| MockedActionServer (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb) | |
| void | publishFeedback (const actionlib_msgs::GoalStatus &, const Feedback &) | 
| void | publishStatus () | 
|  Public Member Functions inherited from actionlib::ActionServerBase< GetPathAction > | |
| ACTION_DEFINITION (GetPathAction) | |
| ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false) | |
| void | cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id) | 
| void | goalCallback (const boost::shared_ptr< const ActionGoal > &goal) | 
| void | registerCancelCallback (boost::function< void(GoalHandle)> cb) | 
| void | registerGoalCallback (boost::function< void(GoalHandle)> cb) | 
| void | start () | 
| virtual | ~ActionServerBase () | 
| Additional Inherited Members | |
|  Protected Member Functions inherited from actionlib::ActionServerBase< GetPathAction > | |
| virtual void | publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)=0 | 
|  Protected Attributes inherited from actionlib::ActionServerBase< GetPathAction > | |
| boost::function< void(GoalHandle)> | cancel_callback_ | 
| boost::function< void(GoalHandle)> | goal_callback_ | 
| boost::shared_ptr< DestructionGuard > | guard_ | 
| GoalIDGenerator | id_generator_ | 
| ros::Time | last_cancel_ | 
| boost::recursive_mutex | lock_ | 
| bool | started_ | 
| std::list< StatusTracker< GetPathAction > > | status_list_ | 
| ros::Duration | status_list_timeout_ | 
Definition at line 51 of file test/planner_action.cpp.
| typedef actionlib::ActionServerBase<GetPathAction> MockedActionServer::ActionServerBase | 
Definition at line 55 of file test/planner_action.cpp.
| typedef actionlib::ServerGoalHandle<GetPathAction> MockedActionServer::GoalHandle | 
Definition at line 54 of file test/planner_action.cpp.
| 
 | inline | 
Definition at line 57 of file test/planner_action.cpp.
| 
 | inlinevirtual | 
Implements actionlib::ActionServerBase< GetPathAction >.
Definition at line 66 of file test/planner_action.cpp.
| MockedActionServer::MOCK_METHOD2 | ( | publishResult | , | 
| void(const actionlib_msgs::GoalStatus &, const Result &) | |||
| ) | 
| 
 | inlinevirtual | 
Implements actionlib::ActionServerBase< GetPathAction >.
Definition at line 70 of file test/planner_action.cpp.
| 
 | inlinevirtual | 
Implements actionlib::ActionServerBase< GetPathAction >.
Definition at line 74 of file test/planner_action.cpp.