#include <planner_action.h>
|
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...
|
|
Definition at line 56 of file planner_action.h.
◆ Ptr
◆ PlannerAction()
◆ runImpl()
◆ 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
-
plan | Input plan to be transformed. |
global_plan | Output 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.
◆ current_goal_pub_
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 |
The documentation for this class was generated from the following files: