Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
mbf_abstract_nav::PlannerAction Class Reference

#include <planner_action.h>

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

Public Types

typedef boost::shared_ptr< PlannerActionPtr
 

Public Member Functions

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

Protected Member Functions

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

Private Attributes

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

Detailed Description

Definition at line 56 of file planner_action.h.

Member Typedef Documentation

◆ Ptr

Definition at line 60 of file planner_action.h.

Constructor & Destructor Documentation

◆ PlannerAction()

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

Definition at line 48 of file src/planner_action.cpp.

Member Function Documentation

◆ runImpl()

void mbf_abstract_nav::PlannerAction::runImpl ( GoalHandle &  goal_handle,
AbstractPlannerExecution execution 
)

Definition at line 58 of file src/planner_action.cpp.

◆ transformPlanToGlobalFrame()

bool mbf_abstract_nav::PlannerAction::transformPlanToGlobalFrame ( const 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 261 of file src/planner_action.cpp.

Member Data Documentation

◆ current_goal_pub_

ros::Publisher mbf_abstract_nav::PlannerAction::current_goal_pub_
private

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

Definition at line 83 of file planner_action.h.

◆ path_seq_count_

unsigned int mbf_abstract_nav::PlannerAction::path_seq_count_
private

Path sequence counter.

Definition at line 86 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 Feb 28 2022 22:49:50