Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav_core_adapter::LocalPlannerAdapter Class Reference

used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base. More...

#include <local_planner_adapter.h>

Inheritance diagram for nav_core_adapter::LocalPlannerAdapter:
Inheritance graph
[legend]

Public Member Functions

bool computeVelocityCommands (geometry_msgs::Twist &cmd_vel) override
 Collect the additional information needed by nav_core2 and call the child computeVelocityCommands. More...
 
void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) override
 Load the nav_core2 local planner and initialize it. More...
 
bool isGoalReached () override
 Collect the additional information needed by nav_core2 and call the child isGoalReached. More...
 
 LocalPlannerAdapter ()
 
bool setPlan (const std::vector< geometry_msgs::PoseStamped > &plan) override
 Convert from 2d to 3d and call child setPlan. More...
 
- Public Member Functions inherited from nav_core::BaseLocalPlanner
virtual ~BaseLocalPlanner ()
 

Protected Member Functions

bool getRobotPose (nav_2d_msgs::Pose2DStamped &pose2d)
 Get the robot pose from the costmap and store as Pose2DStamped. More...
 
bool hasGoalChanged (const nav_2d_msgs::Pose2DStamped &new_goal)
 See if the back of the global plan matches the most recent goal pose. More...
 
- Protected Member Functions inherited from nav_core::BaseLocalPlanner
 BaseLocalPlanner ()
 

Protected Attributes

std::shared_ptr< CostmapAdaptercostmap_adapter_
 
costmap_2d::Costmap2DROScostmap_ros_
 
bool has_active_goal_
 
nav_2d_msgs::Pose2DStamped last_goal_
 
std::shared_ptr< nav_2d_utils::OdomSubscriberodom_sub_
 helper class for subscribing to odometry More...
 
boost::shared_ptr< nav_core2::LocalPlannerplanner_
 
pluginlib::ClassLoader< nav_core2::LocalPlannerplanner_loader_
 
TFListenerPtr tf_
 

Detailed Description

used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base.

Definition at line 53 of file local_planner_adapter.h.

Constructor & Destructor Documentation

nav_core_adapter::LocalPlannerAdapter::LocalPlannerAdapter ( )

Definition at line 48 of file local_planner_adapter.cpp.

Member Function Documentation

bool nav_core_adapter::LocalPlannerAdapter::computeVelocityCommands ( geometry_msgs::Twist &  cmd_vel)
overridevirtual

Collect the additional information needed by nav_core2 and call the child computeVelocityCommands.

Implements nav_core::BaseLocalPlanner.

Definition at line 79 of file local_planner_adapter.cpp.

bool nav_core_adapter::LocalPlannerAdapter::getRobotPose ( nav_2d_msgs::Pose2DStamped &  pose2d)
protected

Get the robot pose from the costmap and store as Pose2DStamped.

Definition at line 172 of file local_planner_adapter.cpp.

bool nav_core_adapter::LocalPlannerAdapter::hasGoalChanged ( const nav_2d_msgs::Pose2DStamped &  new_goal)
protected

See if the back of the global plan matches the most recent goal pose.

Returns
True if the plan has changed

Definition at line 161 of file local_planner_adapter.cpp.

void nav_core_adapter::LocalPlannerAdapter::initialize ( std::string  name,
tf::TransformListener tf,
costmap_2d::Costmap2DROS costmap_ros 
)
overridevirtual

Load the nav_core2 local planner and initialize it.

Implements nav_core::BaseLocalPlanner.

Definition at line 56 of file local_planner_adapter.cpp.

bool nav_core_adapter::LocalPlannerAdapter::isGoalReached ( )
overridevirtual

Collect the additional information needed by nav_core2 and call the child isGoalReached.

Implements nav_core::BaseLocalPlanner.

Definition at line 113 of file local_planner_adapter.cpp.

bool nav_core_adapter::LocalPlannerAdapter::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
overridevirtual

Convert from 2d to 3d and call child setPlan.

Implements nav_core::BaseLocalPlanner.

Definition at line 132 of file local_planner_adapter.cpp.

Member Data Documentation

std::shared_ptr<CostmapAdapter> nav_core_adapter::LocalPlannerAdapter::costmap_adapter_
protected

Definition at line 92 of file local_planner_adapter.h.

costmap_2d::Costmap2DROS* nav_core_adapter::LocalPlannerAdapter::costmap_ros_
protected

Definition at line 93 of file local_planner_adapter.h.

bool nav_core_adapter::LocalPlannerAdapter::has_active_goal_
protected

Definition at line 78 of file local_planner_adapter.h.

nav_2d_msgs::Pose2DStamped nav_core_adapter::LocalPlannerAdapter::last_goal_
protected

Definition at line 77 of file local_planner_adapter.h.

std::shared_ptr<nav_2d_utils::OdomSubscriber> nav_core_adapter::LocalPlannerAdapter::odom_sub_
protected

helper class for subscribing to odometry

Definition at line 83 of file local_planner_adapter.h.

boost::shared_ptr<nav_core2::LocalPlanner> nav_core_adapter::LocalPlannerAdapter::planner_
protected

Definition at line 87 of file local_planner_adapter.h.

pluginlib::ClassLoader<nav_core2::LocalPlanner> nav_core_adapter::LocalPlannerAdapter::planner_loader_
protected

Definition at line 86 of file local_planner_adapter.h.

TFListenerPtr nav_core_adapter::LocalPlannerAdapter::tf_
protected

Definition at line 90 of file local_planner_adapter.h.


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


nav_core_adapter
Author(s):
autogenerated on Wed Jun 26 2019 20:06:25