Public Types | Public Member Functions | Protected Member Functions | Private Attributes
mbf_abstract_nav::PlannerAction Class Reference

#include <planner_action.h>

Inheritance diagram for mbf_abstract_nav::PlannerAction:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< PlannerAction
Ptr

Public Member Functions

 PlannerAction (const std::string &name, const RobotInformation &robot_info)
void run (GoalHandle &goal_handle, AbstractPlannerExecution &execution)

Protected Member Functions

bool transformPlanToGlobalFrame (std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 Transforms a plan to the global frame (global_frame_) coord system.

Private Attributes

ros::Publisher current_goal_pub_
 Publisher to publish the current goal pose, which is used for path planning.
unsigned int path_seq_count_
 Path sequence counter.

Detailed Description

Definition at line 53 of file planner_action.h.


Member Typedef Documentation


Constructor & Destructor Documentation

mbf_abstract_nav::PlannerAction::PlannerAction ( const std::string &  name,
const RobotInformation robot_info 
)

Definition at line 47 of file planner_action.cpp.


Member Function Documentation

Definition at line 57 of file planner_action.cpp.

bool mbf_abstract_nav::PlannerAction::transformPlanToGlobalFrame ( std::vector< geometry_msgs::PoseStamped > &  plan,
std::vector< geometry_msgs::PoseStamped > &  global_plan 
) [protected]

Transforms a plan to the global frame (global_frame_) coord system.

Parameters:
planInput plan to be transformed.
global_planOutput plan, which is then transformed to the global frame.
Returns:
true, if the transformation succeeded, false otherwise

Definition at line 268 of file planner_action.cpp.


Member Data Documentation

Publisher to publish the current goal pose, which is used for path planning.

Definition at line 81 of file planner_action.h.

Path sequence counter.

Definition at line 84 of file planner_action.h.


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


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:35