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>
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< CostmapAdapter > | costmap_adapter_ |
costmap_2d::Costmap2DROS * | costmap_ros_ |
bool | has_active_goal_ |
nav_2d_msgs::Pose2DStamped | last_goal_ |
std::shared_ptr< nav_2d_utils::OdomSubscriber > | odom_sub_ |
helper class for subscribing to odometry More... | |
boost::shared_ptr< nav_core2::LocalPlanner > | planner_ |
pluginlib::ClassLoader< nav_core2::LocalPlanner > | planner_loader_ |
TFListenerPtr | tf_ |
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.
nav_core_adapter::LocalPlannerAdapter::LocalPlannerAdapter | ( | ) |
Definition at line 48 of file local_planner_adapter.cpp.
|
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.
|
protected |
Get the robot pose from the costmap and store as Pose2DStamped.
Definition at line 172 of file local_planner_adapter.cpp.
|
protected |
See if the back of the global plan matches the most recent goal pose.
Definition at line 161 of file local_planner_adapter.cpp.
|
overridevirtual |
Load the nav_core2 local planner and initialize it.
Implements nav_core::BaseLocalPlanner.
Definition at line 56 of file local_planner_adapter.cpp.
|
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.
|
overridevirtual |
Convert from 2d to 3d and call child setPlan.
Implements nav_core::BaseLocalPlanner.
Definition at line 132 of file local_planner_adapter.cpp.
|
protected |
Definition at line 92 of file local_planner_adapter.h.
|
protected |
Definition at line 93 of file local_planner_adapter.h.
|
protected |
Definition at line 78 of file local_planner_adapter.h.
|
protected |
Definition at line 77 of file local_planner_adapter.h.
|
protected |
helper class for subscribing to odometry
Definition at line 83 of file local_planner_adapter.h.
|
protected |
Definition at line 87 of file local_planner_adapter.h.
|
protected |
Definition at line 86 of file local_planner_adapter.h.
|
protected |
Definition at line 90 of file local_planner_adapter.h.