cb_base_navigation
Public Member Functions | Private Member Functions | Private Attributes | List of all members
cb_local_planner::LocalPlannerInterface Class Reference

#include <local_planner_interface.h>

Public Member Functions

 LocalPlannerInterface (costmap_2d::Costmap2DROS *costmap, tf2_ros::Buffer *tf)
 
 ~LocalPlannerInterface ()
 

Private Member Functions

void actionServerPreempt ()
 
void actionServerSetPlan ()
 Action Server stuff. More...
 
void controllerThread ()
 
void doSomeMotionPlanning ()
 
bool isGoalSet ()
 
void topicGoalCallback (const cb_base_navigation_msgs::LocalPlannerActionGoalConstPtr &goal)
 topic goal cb More...
 
bool updateEndGoalOrientation ()
 Helper functions. More...
 

Private Attributes

std::unique_ptr< actionlib::SimpleActionServer< cb_base_navigation_msgs::LocalPlannerAction > > action_server_
 
double controller_frequency_
 
std::unique_ptr< std::threadcontroller_thread_
 
costmap_2d::Costmap2DROScostmap_
 Costmaps. More...
 
ros::ServiceClient ed_client_
 World model client. More...
 
cb_base_navigation_msgs::LocalPlannerFeedback feedback_
 
std::string global_frame_
 
cb_base_navigation_msgs::LocalPlannerGoal goal_
 
boost::mutex goal_mtx_
 
boost::shared_ptr< nav_core::BaseLocalPlanner > local_planner_
 Planners + loaders. More...
 
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > lp_loader_
 
std::string robot_base_frame_
 Frame names + Tranforms. More...
 
tf2_ros::Buffer * tf_
 
ros::Subscriber topic_sub_
 
ros::Publisher vel_pub_
 ROS Communication. More...
 
Visualization vis
 Visualization. More...
 

Detailed Description

Definition at line 43 of file local_planner_interface.h.

Constructor & Destructor Documentation

◆ LocalPlannerInterface()

cb_local_planner::LocalPlannerInterface::LocalPlannerInterface ( costmap_2d::Costmap2DROS costmap,
tf2_ros::Buffer *  tf 
)

Definition at line 30 of file local_planner_interface.cpp.

◆ ~LocalPlannerInterface()

cb_local_planner::LocalPlannerInterface::~LocalPlannerInterface ( )

Definition at line 21 of file local_planner_interface.cpp.

Member Function Documentation

◆ actionServerPreempt()

void cb_local_planner::LocalPlannerInterface::actionServerPreempt ( )
private

Definition at line 114 of file local_planner_interface.cpp.

◆ actionServerSetPlan()

void cb_local_planner::LocalPlannerInterface::actionServerSetPlan ( )
private

Action Server stuff.

Definition at line 98 of file local_planner_interface.cpp.

◆ controllerThread()

void cb_local_planner::LocalPlannerInterface::controllerThread ( )
private

Definition at line 122 of file local_planner_interface.cpp.

◆ doSomeMotionPlanning()

void cb_local_planner::LocalPlannerInterface::doSomeMotionPlanning ( )
private

Definition at line 226 of file local_planner_interface.cpp.

◆ isGoalSet()

bool cb_local_planner::LocalPlannerInterface::isGoalSet ( )
inlineprivate

Definition at line 59 of file local_planner_interface.h.

◆ topicGoalCallback()

void cb_local_planner::LocalPlannerInterface::topicGoalCallback ( const cb_base_navigation_msgs::LocalPlannerActionGoalConstPtr &  goal)
private

topic goal cb

Definition at line 82 of file local_planner_interface.cpp.

◆ updateEndGoalOrientation()

bool cb_local_planner::LocalPlannerInterface::updateEndGoalOrientation ( )
private

Helper functions.

Definition at line 266 of file local_planner_interface.cpp.

Member Data Documentation

◆ action_server_

std::unique_ptr<actionlib::SimpleActionServer<cb_base_navigation_msgs::LocalPlannerAction> > cb_local_planner::LocalPlannerInterface::action_server_
private

Definition at line 64 of file local_planner_interface.h.

◆ controller_frequency_

double cb_local_planner::LocalPlannerInterface::controller_frequency_
private

Definition at line 81 of file local_planner_interface.h.

◆ controller_thread_

std::unique_ptr<std::thread> cb_local_planner::LocalPlannerInterface::controller_thread_
private

Definition at line 54 of file local_planner_interface.h.

◆ costmap_

costmap_2d::Costmap2DROS* cb_local_planner::LocalPlannerInterface::costmap_
private

Costmaps.

Definition at line 88 of file local_planner_interface.h.

◆ ed_client_

ros::ServiceClient cb_local_planner::LocalPlannerInterface::ed_client_
private

World model client.

Definition at line 70 of file local_planner_interface.h.

◆ feedback_

cb_base_navigation_msgs::LocalPlannerFeedback cb_local_planner::LocalPlannerInterface::feedback_
private

Definition at line 76 of file local_planner_interface.h.

◆ global_frame_

std::string cb_local_planner::LocalPlannerInterface::global_frame_
private

Definition at line 84 of file local_planner_interface.h.

◆ goal_

cb_base_navigation_msgs::LocalPlannerGoal cb_local_planner::LocalPlannerInterface::goal_
private

Definition at line 75 of file local_planner_interface.h.

◆ goal_mtx_

boost::mutex cb_local_planner::LocalPlannerInterface::goal_mtx_
private

Definition at line 53 of file local_planner_interface.h.

◆ local_planner_

boost::shared_ptr<nav_core::BaseLocalPlanner> cb_local_planner::LocalPlannerInterface::local_planner_
private

Planners + loaders.

Definition at line 79 of file local_planner_interface.h.

◆ lp_loader_

pluginlib::ClassLoader<nav_core::BaseLocalPlanner> cb_local_planner::LocalPlannerInterface::lp_loader_
private

Definition at line 80 of file local_planner_interface.h.

◆ robot_base_frame_

std::string cb_local_planner::LocalPlannerInterface::robot_base_frame_
private

Frame names + Tranforms.

Definition at line 84 of file local_planner_interface.h.

◆ tf_

tf2_ros::Buffer* cb_local_planner::LocalPlannerInterface::tf_
private

Definition at line 85 of file local_planner_interface.h.

◆ topic_sub_

ros::Subscriber cb_local_planner::LocalPlannerInterface::topic_sub_
private

Definition at line 63 of file local_planner_interface.h.

◆ vel_pub_

ros::Publisher cb_local_planner::LocalPlannerInterface::vel_pub_
private

ROS Communication.

Definition at line 62 of file local_planner_interface.h.

◆ vis

Visualization cb_local_planner::LocalPlannerInterface::vis
private

Visualization.

Definition at line 94 of file local_planner_interface.h.


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